39 #include <kdl/jntarray.hpp>
40 #include <kdl_parser/kdl_parser.hpp>
41 #include <kdl/tree.hpp>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
47 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_dynamics_solver.dynamics_solver");
51 inline geometry_msgs::msg::Vector3 transformVector(
const Eigen::Isometry3d& transform,
52 const geometry_msgs::msg::Vector3& vector)
57 p = transform.linear() *
p;
59 geometry_msgs::msg::Vector3 result;
69 const geometry_msgs::msg::Vector3& gravity_vector)
71 robot_model_ = robot_model;
72 joint_model_group_ = robot_model_->getJointModelGroup(group_name);
73 if (!joint_model_group_)
76 if (!joint_model_group_->
isChain())
78 RCLCPP_ERROR(LOGGER,
"Group '%s' is not a chain. Will not initialize dynamics solver", group_name.c_str());
79 joint_model_group_ =
nullptr;
85 RCLCPP_ERROR(LOGGER,
"Group '%s' has a mimic joint. Will not initialize dynamics solver", group_name.c_str());
86 joint_model_group_ =
nullptr;
93 RCLCPP_ERROR(LOGGER,
"Group '%s' does not have a parent link", group_name.c_str());
94 joint_model_group_ =
nullptr;
101 RCLCPP_DEBUG(LOGGER,
"Base name: '%s', Tip name: '%s'", base_name_.c_str(), tip_name_.c_str());
103 const urdf::ModelInterfaceSharedPtr urdf_model = robot_model_->getURDF();
104 const srdf::ModelConstSharedPtr srdf_model = robot_model_->getSRDF();
107 if (!kdl_parser::treeFromUrdfModel(*urdf_model, tree))
109 RCLCPP_ERROR(LOGGER,
"Could not initialize tree object");
110 joint_model_group_ =
nullptr;
113 if (!tree.getChain(base_name_, tip_name_, kdl_chain_))
115 RCLCPP_ERROR(LOGGER,
"Could not initialize chain object");
116 joint_model_group_ =
nullptr;
119 num_joints_ = kdl_chain_.getNrOfJoints();
120 num_segments_ = kdl_chain_.getNrOfSegments();
122 state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
123 state_->setToDefaultValues();
125 const std::vector<std::string>& joint_model_names = joint_model_group_->
getJointModelNames();
126 for (
const std::string& joint_model_name : joint_model_names)
128 const urdf::Joint* ujoint = urdf_model->getJoint(joint_model_name).get();
129 if (ujoint && ujoint->limits)
130 max_torques_.push_back(ujoint->limits->effort);
132 max_torques_.push_back(0.0);
135 KDL::Vector gravity(gravity_vector.x, gravity_vector.y,
137 gravity_ = gravity.Norm();
138 RCLCPP_DEBUG(LOGGER,
"Gravity norm set to %f", gravity_);
140 chain_id_solver_ = std::make_shared<KDL::ChainIdSolver_RNE>(kdl_chain_, gravity);
144 const std::vector<double>& joint_accelerations,
145 const std::vector<geometry_msgs::msg::Wrench>& wrenches,
146 std::vector<double>& torques)
const
148 if (!joint_model_group_)
150 RCLCPP_DEBUG(LOGGER,
"Did not construct DynamicsSolver object properly. "
151 "Check error logs.");
154 if (joint_angles.size() != num_joints_)
156 RCLCPP_ERROR(LOGGER,
"Joint angles vector should be size %d", num_joints_);
159 if (joint_velocities.size() != num_joints_)
161 RCLCPP_ERROR(LOGGER,
"Joint velocities vector should be size %d", num_joints_);
164 if (joint_accelerations.size() != num_joints_)
166 RCLCPP_ERROR(LOGGER,
"Joint accelerations vector should be size %d", num_joints_);
169 if (wrenches.size() != num_segments_)
171 RCLCPP_ERROR(LOGGER,
"Wrenches vector should be size %d", num_segments_);
174 if (torques.size() != num_joints_)
176 RCLCPP_ERROR(LOGGER,
"Torques vector should be size %d", num_joints_);
180 KDL::JntArray kdl_angles(num_joints_), kdl_velocities(num_joints_), kdl_accelerations(num_joints_),
181 kdl_torques(num_joints_);
182 KDL::Wrenches kdl_wrenches(num_segments_);
184 for (
unsigned int i = 0; i < num_joints_; ++i)
186 kdl_angles(i) = joint_angles[i];
187 kdl_velocities(i) = joint_velocities[i];
188 kdl_accelerations(i) = joint_accelerations[i];
191 for (
unsigned int i = 0; i < num_segments_; ++i)
193 kdl_wrenches[i](0) = wrenches[i].force.x;
194 kdl_wrenches[i](1) = wrenches[i].force.y;
195 kdl_wrenches[i](2) = wrenches[i].force.z;
197 kdl_wrenches[i](3) = wrenches[i].torque.x;
198 kdl_wrenches[i](4) = wrenches[i].torque.y;
199 kdl_wrenches[i](5) = wrenches[i].torque.z;
202 if (chain_id_solver_->CartToJnt(kdl_angles, kdl_velocities, kdl_accelerations, kdl_wrenches, kdl_torques) < 0)
204 RCLCPP_ERROR(LOGGER,
"Something went wrong computing torques");
208 for (
unsigned int i = 0; i < num_joints_; ++i)
209 torques[i] = kdl_torques(i);
215 unsigned int& joint_saturated)
const
217 if (!joint_model_group_)
219 RCLCPP_DEBUG(LOGGER,
"Did not construct DynamicsSolver object properly. "
220 "Check error logs.");
223 if (joint_angles.size() != num_joints_)
225 RCLCPP_ERROR(LOGGER,
"Joint angles vector should be size %d", num_joints_);
228 std::vector<double> joint_velocities(num_joints_, 0.0), joint_accelerations(num_joints_, 0.0);
229 std::vector<double> torques(num_joints_, 0.0), zero_torques(num_joints_, 0.0);
231 std::vector<geometry_msgs::msg::Wrench> wrenches(num_segments_);
232 if (!
getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, zero_torques))
235 for (
unsigned int i = 0; i < num_joints_; ++i)
237 if (fabs(zero_torques[i]) >= max_torques_[i])
245 state_->setJointGroupPositions(joint_model_group_, joint_angles);
246 const Eigen::Isometry3d& base_frame = state_->getFrameTransform(base_name_);
247 const Eigen::Isometry3d& tip_frame = state_->getFrameTransform(tip_name_);
248 Eigen::Isometry3d transform = tip_frame.inverse() * base_frame;
249 wrenches.back().force.z = 1.0;
250 wrenches.back().force = transformVector(transform, wrenches.back().force);
251 wrenches.back().torque = transformVector(transform, wrenches.back().torque);
253 RCLCPP_DEBUG(LOGGER,
"New wrench (local frame): %f %f %f", wrenches.back().force.x, wrenches.back().force.y,
254 wrenches.back().force.z);
256 if (!
getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, torques))
259 double min_payload = std::numeric_limits<double>::max();
260 for (
unsigned int i = 0; i < num_joints_; ++i)
262 double payload_joint = std::max<double>((max_torques_[i] - zero_torques[i]) / (torques[i] - zero_torques[i]),
263 (-max_torques_[i] - zero_torques[i]) /
264 (torques[i] - zero_torques[i]));
265 RCLCPP_DEBUG(LOGGER,
"Joint: %d, Actual Torque: %f, Max Allowed: %f, Gravity: %f", i, torques[i], max_torques_[i],
267 RCLCPP_DEBUG(LOGGER,
"Joint: %d, Payload Allowed (N): %f", i, payload_joint);
268 if (payload_joint < min_payload)
270 min_payload = payload_joint;
274 payload = min_payload / gravity_;
275 RCLCPP_DEBUG(LOGGER,
"Max payload (kg): %f", payload);
280 std::vector<double>& joint_torques)
const
282 if (!joint_model_group_)
284 RCLCPP_DEBUG(LOGGER,
"Did not construct DynamicsSolver object properly. "
285 "Check error logs.");
288 if (joint_angles.size() != num_joints_)
290 RCLCPP_ERROR(LOGGER,
"Joint angles vector should be size %d", num_joints_);
293 if (joint_torques.size() != num_joints_)
295 RCLCPP_ERROR(LOGGER,
"Joint torques vector should be size %d", num_joints_);
298 std::vector<double> joint_velocities(num_joints_, 0.0), joint_accelerations(num_joints_, 0.0);
299 std::vector<geometry_msgs::msg::Wrench> wrenches(num_segments_);
300 state_->setJointGroupPositions(joint_model_group_, joint_angles);
302 const Eigen::Isometry3d& base_frame = state_->getFrameTransform(base_name_);
303 const Eigen::Isometry3d& tip_frame = state_->getFrameTransform(tip_name_);
304 Eigen::Isometry3d transform = tip_frame.inverse() * base_frame;
305 wrenches.back().force.z = payload * gravity_;
306 wrenches.back().force = transformVector(transform, wrenches.back().force);
307 wrenches.back().torque = transformVector(transform, wrenches.back().torque);
309 RCLCPP_DEBUG(LOGGER,
"New wrench (local frame): %f %f %f", wrenches.back().force.x, wrenches.back().force.y,
310 wrenches.back().force.z);
312 return getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, joint_torques);
const std::vector< double > & getMaxTorques() const
Get maximum torques for this group.
DynamicsSolver(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const geometry_msgs::msg::Vector3 &gravity_vector)
Initialize the dynamics solver.
bool getMaxPayload(const std::vector< double > &joint_angles, double &payload, unsigned int &joint_saturated) const
Get the maximum payload for this group (in kg). Payload is the weight that this group can hold when t...
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
Get the torques (the order of all input and output is the same as the order of joints for this group ...
bool getPayloadTorques(const std::vector< double > &joint_angles, double payload, std::vector< double > &joint_torques) const
Get torques corresponding to a particular payload value. Payload is the weight that this group can ho...
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
bool isChain() const
Check if this group is a linear chain.
const std::vector< const JointModel * > & getJointRoots() const
Unlike a complete kinematic model, a group may contain disconnected parts of the kinematic tree – a s...
const std::vector< std::string > & getJointModelNames() const
Get the names of the joints in this group. These are the names of the joints returned by getJointMode...
const std::vector< const JointModel * > & getMimicJointModels() const
Get the mimic joints that are part of this group.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint,...
const std::string & getName() const
The name of this link.
This namespace includes the dynamics_solver library.
Vec3fX< details::Vec3Data< double > > Vector3d