76 const geometry_msgs::msg::Vector3& gravity_vector)
78 robot_model_ = robot_model;
79 joint_model_group_ = robot_model_->getJointModelGroup(group_name);
80 if (!joint_model_group_)
83 if (!joint_model_group_->
isChain())
85 RCLCPP_ERROR(getLogger(),
"Group '%s' is not a chain. Will not initialize dynamics solver", group_name.c_str());
86 joint_model_group_ =
nullptr;
92 RCLCPP_ERROR(getLogger(),
"Group '%s' has a mimic joint. Will not initialize dynamics solver", group_name.c_str());
93 joint_model_group_ =
nullptr;
100 RCLCPP_ERROR(getLogger(),
"Group '%s' does not have a parent link", group_name.c_str());
101 joint_model_group_ =
nullptr;
108 RCLCPP_DEBUG(getLogger(),
"Base name: '%s', Tip name: '%s'", base_name_.c_str(), tip_name_.c_str());
110 const urdf::ModelInterfaceSharedPtr urdf_model = robot_model_->getURDF();
111 const srdf::ModelConstSharedPtr srdf_model = robot_model_->getSRDF();
114 if (!kdl_parser::treeFromUrdfModel(*urdf_model, tree))
116 RCLCPP_ERROR(getLogger(),
"Could not initialize tree object");
117 joint_model_group_ =
nullptr;
120 if (!tree.getChain(base_name_, tip_name_, kdl_chain_))
122 RCLCPP_ERROR(getLogger(),
"Could not initialize chain object");
123 joint_model_group_ =
nullptr;
126 num_joints_ = kdl_chain_.getNrOfJoints();
127 num_segments_ = kdl_chain_.getNrOfSegments();
129 state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
130 state_->setToDefaultValues();
132 const std::vector<std::string>& joint_model_names = joint_model_group_->
getJointModelNames();
133 for (
const std::string& joint_model_name : joint_model_names)
135 const urdf::Joint* ujoint = urdf_model->getJoint(joint_model_name).get();
136 if (ujoint && ujoint->limits)
138 max_torques_.push_back(ujoint->limits->effort);
142 max_torques_.push_back(0.0);
146 KDL::Vector gravity(gravity_vector.x, gravity_vector.y,
148 gravity_ = gravity.Norm();
149 RCLCPP_DEBUG(getLogger(),
"Gravity norm set to %f", gravity_);
151 chain_id_solver_ = std::make_shared<KDL::ChainIdSolver_RNE>(kdl_chain_, gravity);
155 const std::vector<double>& joint_accelerations,
156 const std::vector<geometry_msgs::msg::Wrench>& wrenches,
157 std::vector<double>& torques)
const
159 if (!joint_model_group_)
161 RCLCPP_DEBUG(getLogger(),
"Did not construct DynamicsSolver object properly. "
162 "Check error logs.");
165 if (joint_angles.size() != num_joints_)
167 RCLCPP_ERROR(getLogger(),
"Joint angles vector should be size %d", num_joints_);
170 if (joint_velocities.size() != num_joints_)
172 RCLCPP_ERROR(getLogger(),
"Joint velocities vector should be size %d", num_joints_);
175 if (joint_accelerations.size() != num_joints_)
177 RCLCPP_ERROR(getLogger(),
"Joint accelerations vector should be size %d", num_joints_);
180 if (wrenches.size() != num_segments_)
182 RCLCPP_ERROR(getLogger(),
"Wrenches vector should be size %d", num_segments_);
185 if (torques.size() != num_joints_)
187 RCLCPP_ERROR(getLogger(),
"Torques vector should be size %d", num_joints_);
191 KDL::JntArray kdl_angles(num_joints_), kdl_velocities(num_joints_), kdl_accelerations(num_joints_),
192 kdl_torques(num_joints_);
193 KDL::Wrenches kdl_wrenches(num_segments_);
195 for (
unsigned int i = 0; i < num_joints_; ++i)
197 kdl_angles(i) = joint_angles[i];
198 kdl_velocities(i) = joint_velocities[i];
199 kdl_accelerations(i) = joint_accelerations[i];
202 for (
unsigned int i = 0; i < num_segments_; ++i)
204 kdl_wrenches[i](0) = wrenches[i].force.x;
205 kdl_wrenches[i](1) = wrenches[i].force.y;
206 kdl_wrenches[i](2) = wrenches[i].force.z;
208 kdl_wrenches[i](3) = wrenches[i].torque.x;
209 kdl_wrenches[i](4) = wrenches[i].torque.y;
210 kdl_wrenches[i](5) = wrenches[i].torque.z;
213 if (chain_id_solver_->CartToJnt(kdl_angles, kdl_velocities, kdl_accelerations, kdl_wrenches, kdl_torques) < 0)
215 RCLCPP_ERROR(getLogger(),
"Something went wrong computing torques");
219 for (
unsigned int i = 0; i < num_joints_; ++i)
220 torques[i] = kdl_torques(i);
226 unsigned int& joint_saturated)
const
228 if (!joint_model_group_)
230 RCLCPP_DEBUG(getLogger(),
"Did not construct DynamicsSolver object properly. "
231 "Check error logs.");
234 if (joint_angles.size() != num_joints_)
236 RCLCPP_ERROR(getLogger(),
"Joint angles vector should be size %d", num_joints_);
239 std::vector<double> joint_velocities(num_joints_, 0.0), joint_accelerations(num_joints_, 0.0);
240 std::vector<double> torques(num_joints_, 0.0), zero_torques(num_joints_, 0.0);
242 std::vector<geometry_msgs::msg::Wrench> wrenches(num_segments_);
243 if (!
getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, zero_torques))
246 for (
unsigned int i = 0; i < num_joints_; ++i)
248 if (fabs(zero_torques[i]) >= max_torques_[i])
256 state_->setJointGroupPositions(joint_model_group_, joint_angles);
257 const Eigen::Isometry3d& base_frame = state_->getFrameTransform(base_name_);
258 const Eigen::Isometry3d& tip_frame = state_->getFrameTransform(tip_name_);
259 Eigen::Isometry3d transform = tip_frame.inverse() * base_frame;
260 wrenches.back().force.z = 1.0;
261 wrenches.back().force = transformVector(transform, wrenches.back().force);
262 wrenches.back().torque = transformVector(transform, wrenches.back().torque);
264 RCLCPP_DEBUG(getLogger(),
"New wrench (local frame): %f %f %f", wrenches.back().force.x, wrenches.back().force.y,
265 wrenches.back().force.z);
267 if (!
getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, torques))
270 double min_payload = std::numeric_limits<double>::max();
271 for (
unsigned int i = 0; i < num_joints_; ++i)
273 double payload_joint = std::max<double>((max_torques_[i] - zero_torques[i]) / (torques[i] - zero_torques[i]),
274 (-max_torques_[i] - zero_torques[i]) /
275 (torques[i] - zero_torques[i]));
276 RCLCPP_DEBUG(getLogger(),
"Joint: %d, Actual Torque: %f, Max Allowed: %f, Gravity: %f", i, torques[i],
277 max_torques_[i], zero_torques[i]);
278 RCLCPP_DEBUG(getLogger(),
"Joint: %d, Payload Allowed (N): %f", i, payload_joint);
279 if (payload_joint < min_payload)
281 min_payload = payload_joint;
285 payload = min_payload / gravity_;
286 RCLCPP_DEBUG(getLogger(),
"Max payload (kg): %f", payload);
291 std::vector<double>& joint_torques)
const
293 if (!joint_model_group_)
295 RCLCPP_DEBUG(getLogger(),
"Did not construct DynamicsSolver object properly. "
296 "Check error logs.");
299 if (joint_angles.size() != num_joints_)
301 RCLCPP_ERROR(getLogger(),
"Joint angles vector should be size %d", num_joints_);
304 if (joint_torques.size() != num_joints_)
306 RCLCPP_ERROR(getLogger(),
"Joint torques vector should be size %d", num_joints_);
309 std::vector<double> joint_velocities(num_joints_, 0.0), joint_accelerations(num_joints_, 0.0);
310 std::vector<geometry_msgs::msg::Wrench> wrenches(num_segments_);
311 state_->setJointGroupPositions(joint_model_group_, joint_angles);
313 const Eigen::Isometry3d& base_frame = state_->getFrameTransform(base_name_);
314 const Eigen::Isometry3d& tip_frame = state_->getFrameTransform(tip_name_);
315 Eigen::Isometry3d transform = tip_frame.inverse() * base_frame;
316 wrenches.back().force.z = payload * gravity_;
317 wrenches.back().force = transformVector(transform, wrenches.back().force);
318 wrenches.back().torque = transformVector(transform, wrenches.back().torque);
320 RCLCPP_DEBUG(getLogger(),
"New wrench (local frame): %f %f %f", wrenches.back().force.x, wrenches.back().force.y,
321 wrenches.back().force.z);
323 return getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, joint_torques);
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 ...