Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Improvement in dynamics solver port to ROS 2 #89

Merged
merged 4 commits into from
Jun 12, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 5 additions & 1 deletion moveit_core/dynamics_solver/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
set(MOVEIT_LIB_NAME moveit_dynamics_solver)

add_library(${MOVEIT_LIB_NAME} src/dynamics_solver.cpp)
add_library(${MOVEIT_LIB_NAME} SHARED src/dynamics_solver.cpp)
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")

ament_target_dependencies(${MOVEIT_LIB_NAME}
Expand All @@ -11,6 +11,10 @@ ament_target_dependencies(${MOVEIT_LIB_NAME}
visualization_msgs
kdl_parser)

target_link_libraries(${MOVEIT_LIB_NAME}
moveit_robot_state
)

install(TARGETS ${MOVEIT_LIB_NAME}
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,8 @@ class DynamicsSolver
* @return False if any of the input vectors are of the wrong size
*/
bool getTorques(const std::vector<double>& joint_angles, const std::vector<double>& joint_velocities,
const std::vector<double>& joint_accelerations, const std::vector<geometry_msgs::msg::Wrench>& wrenches,
std::vector<double>& torques) const;
const std::vector<double>& joint_accelerations,
const std::vector<geometry_msgs::msg::Wrench>& wrenches, std::vector<double>& torques) const;

/**
* @brief Get the maximum payload for this group (in kg). Payload is
Expand Down
73 changes: 37 additions & 36 deletions moveit_core/dynamics_solver/src/dynamics_solver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,12 +48,12 @@

namespace dynamics_solver
{

rclcpp::Logger LOGGER = rclcpp::get_logger("moveit").get_child("dynamics_solver");
rclcpp::Logger LOGGER_DYNAMICS_SOLVER = rclcpp::get_logger("moveit").get_child("dynamics_solver");

namespace
{
inline geometry_msgs::msg::Vector3 transformVector(const Eigen::Isometry3d& transform, const geometry_msgs::msg::Vector3& vector)
inline geometry_msgs::msg::Vector3 transformVector(const Eigen::Isometry3d& transform,
const geometry_msgs::msg::Vector3& vector)
{
Eigen::Vector3d p;
p = Eigen::Vector3d(vector.x, vector.y, vector.z);
Expand All @@ -78,46 +78,46 @@ DynamicsSolver::DynamicsSolver(const robot_model::RobotModelConstPtr& robot_mode

if (!joint_model_group_->isChain())
{
RCLCPP_ERROR(LOGGER, "Group '%s' is not a chain. Will not initialize dynamics solver",
group_name.c_str());
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Group '%s' is not a chain. Will not initialize dynamics solver",
group_name.c_str());
joint_model_group_ = nullptr;
return;
}

if (!joint_model_group_->getMimicJointModels().empty())
{
RCLCPP_ERROR(LOGGER, "Group '%s' has a mimic joint. Will not initialize dynamics solver",
group_name.c_str());
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Group '%s' has a mimic joint. Will not initialize dynamics solver",
group_name.c_str());
joint_model_group_ = nullptr;
return;
}

const robot_model::JointModel* joint = joint_model_group_->getJointRoots()[0];
if (!joint->getParentLinkModel())
{
RCLCPP_ERROR(LOGGER, "Group '%s' does not have a parent link", group_name.c_str());
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Group '%s' does not have a parent link", group_name.c_str());
joint_model_group_ = nullptr;
return;
}

base_name_ = joint->getParentLinkModel()->getName();

tip_name_ = joint_model_group_->getLinkModelNames().back();
RCLCPP_DEBUG(LOGGER, "Base name: '%s', Tip name: '%s'", base_name_.c_str(), tip_name_.c_str());
RCLCPP_DEBUG(LOGGER_DYNAMICS_SOLVER, "Base name: '%s', Tip name: '%s'", base_name_.c_str(), tip_name_.c_str());

const urdf::ModelInterfaceSharedPtr urdf_model = robot_model_->getURDF();
const srdf::ModelConstSharedPtr srdf_model = robot_model_->getSRDF();
KDL::Tree tree;

if (!kdl_parser::treeFromUrdfModel(*urdf_model, tree))
{
RCLCPP_ERROR(LOGGER, "Could not initialize tree object");
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Could not initialize tree object");
joint_model_group_ = nullptr;
return;
}
if (!tree.getChain(base_name_, tip_name_, kdl_chain_))
{
RCLCPP_ERROR(LOGGER, "Could not initialize chain object");
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Could not initialize chain object");
joint_model_group_ = nullptr;
return;
}
Expand All @@ -140,44 +140,45 @@ DynamicsSolver::DynamicsSolver(const robot_model::RobotModelConstPtr& robot_mode
KDL::Vector gravity(gravity_vector.x, gravity_vector.y,
gravity_vector.z); // \todo Not sure if KDL expects the negative of this (Sachin)
gravity_ = gravity.Norm();
RCLCPP_DEBUG(LOGGER, "Gravity norm set to %f", gravity_);
RCLCPP_DEBUG(LOGGER_DYNAMICS_SOLVER, "Gravity norm set to %f", gravity_);

chain_id_solver_.reset(new KDL::ChainIdSolver_RNE(kdl_chain_, gravity));
}

bool DynamicsSolver::getTorques(const std::vector<double>& joint_angles, const std::vector<double>& joint_velocities,
const std::vector<double>& joint_accelerations,
const std::vector<geometry_msgs::msg::Wrench>& wrenches, std::vector<double>& torques) const
const std::vector<geometry_msgs::msg::Wrench>& wrenches,
std::vector<double>& torques) const
{
if (!joint_model_group_)
{
RCLCPP_DEBUG(LOGGER, "Did not construct DynamicsSolver object properly. "
"Check error logs.");
RCLCPP_DEBUG(LOGGER_DYNAMICS_SOLVER, "Did not construct DynamicsSolver object properly. "
"Check error logs.");
return false;
}
if (joint_angles.size() != num_joints_)
{
RCLCPP_ERROR(LOGGER, "Joint angles vector should be size %d", num_joints_);
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Joint angles vector should be size %d", num_joints_);
return false;
}
if (joint_velocities.size() != num_joints_)
{
RCLCPP_ERROR(LOGGER, "Joint velocities vector should be size %d", num_joints_);
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Joint velocities vector should be size %d", num_joints_);
return false;
}
if (joint_accelerations.size() != num_joints_)
{
RCLCPP_ERROR(LOGGER, "Joint accelerations vector should be size %d", num_joints_);
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Joint accelerations vector should be size %d", num_joints_);
return false;
}
if (wrenches.size() != num_segments_)
{
RCLCPP_ERROR(LOGGER, "Wrenches vector should be size %d", num_segments_);
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Wrenches vector should be size %d", num_segments_);
return false;
}
if (torques.size() != num_joints_)
{
RCLCPP_ERROR(LOGGER, "Torques vector should be size %d", num_joints_);
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Torques vector should be size %d", num_joints_);
return false;
}

Expand Down Expand Up @@ -205,7 +206,7 @@ bool DynamicsSolver::getTorques(const std::vector<double>& joint_angles, const s

if (chain_id_solver_->CartToJnt(kdl_angles, kdl_velocities, kdl_accelerations, kdl_wrenches, kdl_torques) < 0)
{
RCLCPP_ERROR(LOGGER, "Something went wrong computing torques");
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Something went wrong computing torques");
return false;
}

Expand All @@ -220,13 +221,13 @@ bool DynamicsSolver::getMaxPayload(const std::vector<double>& joint_angles, doub
{
if (!joint_model_group_)
{
RCLCPP_DEBUG(LOGGER, "Did not construct DynamicsSolver object properly. "
"Check error logs.");
RCLCPP_DEBUG(LOGGER_DYNAMICS_SOLVER, "Did not construct DynamicsSolver object properly. "
"Check error logs.");
return false;
}
if (joint_angles.size() != num_joints_)
{
RCLCPP_ERROR(LOGGER, "Joint angles vector should be size %d", num_joints_);
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Joint angles vector should be size %d", num_joints_);
return false;
}
std::vector<double> joint_velocities(num_joints_, 0.0), joint_accelerations(num_joints_, 0.0);
Expand Down Expand Up @@ -254,8 +255,8 @@ bool DynamicsSolver::getMaxPayload(const std::vector<double>& joint_angles, doub
wrenches.back().force = transformVector(transform, wrenches.back().force);
wrenches.back().torque = transformVector(transform, wrenches.back().torque);

RCLCPP_DEBUG(LOGGER, "New wrench (local frame): %f %f %f", wrenches.back().force.x,
wrenches.back().force.y, wrenches.back().force.z);
RCLCPP_DEBUG(LOGGER_DYNAMICS_SOLVER, "New wrench (local frame): %f %f %f", wrenches.back().force.x,
wrenches.back().force.y, wrenches.back().force.z);

if (!getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, torques))
return false;
Expand All @@ -266,17 +267,17 @@ bool DynamicsSolver::getMaxPayload(const std::vector<double>& joint_angles, doub
double payload_joint = std::max<double>((max_torques_[i] - zero_torques[i]) / (torques[i] - zero_torques[i]),
(-max_torques_[i] - zero_torques[i]) /
(torques[i] - zero_torques[i])); // because we set the payload to 1.0
RCLCPP_DEBUG(LOGGER, "Joint: %d, Actual Torque: %f, Max Allowed: %f, Gravity: %f", i, torques[i],
max_torques_[i], zero_torques[i]);
RCLCPP_DEBUG(LOGGER, "Joint: %d, Payload Allowed (N): %f", i, payload_joint);
RCLCPP_DEBUG(LOGGER_DYNAMICS_SOLVER, "Joint: %d, Actual Torque: %f, Max Allowed: %f, Gravity: %f", i, torques[i],
max_torques_[i], zero_torques[i]);
RCLCPP_DEBUG(LOGGER_DYNAMICS_SOLVER, "Joint: %d, Payload Allowed (N): %f", i, payload_joint);
if (payload_joint < min_payload)
{
min_payload = payload_joint;
joint_saturated = i;
}
}
payload = min_payload / gravity_;
RCLCPP_DEBUG(LOGGER, "Max payload (kg): %f", payload);
RCLCPP_DEBUG(LOGGER_DYNAMICS_SOLVER, "Max payload (kg): %f", payload);
return true;
}

Expand All @@ -285,18 +286,18 @@ bool DynamicsSolver::getPayloadTorques(const std::vector<double>& joint_angles,
{
if (!joint_model_group_)
{
RCLCPP_DEBUG(LOGGER, "Did not construct DynamicsSolver object properly. "
"Check error logs.");
RCLCPP_DEBUG(LOGGER_DYNAMICS_SOLVER, "Did not construct DynamicsSolver object properly. "
"Check error logs.");
return false;
}
if (joint_angles.size() != num_joints_)
{
RCLCPP_ERROR(LOGGER, "Joint angles vector should be size %d", num_joints_);
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Joint angles vector should be size %d", num_joints_);
return false;
}
if (joint_torques.size() != num_joints_)
{
RCLCPP_ERROR(LOGGER, "Joint torques vector should be size %d", num_joints_);
RCLCPP_ERROR(LOGGER_DYNAMICS_SOLVER, "Joint torques vector should be size %d", num_joints_);
return false;
}
std::vector<double> joint_velocities(num_joints_, 0.0), joint_accelerations(num_joints_, 0.0);
Expand All @@ -310,8 +311,8 @@ bool DynamicsSolver::getPayloadTorques(const std::vector<double>& joint_angles,
wrenches.back().force = transformVector(transform, wrenches.back().force);
wrenches.back().torque = transformVector(transform, wrenches.back().torque);

RCLCPP_DEBUG(LOGGER, "New wrench (local frame): %f %f %f", wrenches.back().force.x,
wrenches.back().force.y, wrenches.back().force.z);
RCLCPP_DEBUG(LOGGER_DYNAMICS_SOLVER, "New wrench (local frame): %f %f %f", wrenches.back().force.x,
wrenches.back().force.y, wrenches.back().force.z);

return getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, joint_torques);
}
Expand Down