moveit2
The MoveIt Motion Planning Framework for ROS 2.
dynamics_solver.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Sachin Chitta */
36 
38 // KDL
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>
44 
45 namespace dynamics_solver
46 {
47 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_dynamics_solver.dynamics_solver");
48 
49 namespace
50 {
51 inline geometry_msgs::msg::Vector3 transformVector(const Eigen::Isometry3d& transform,
52  const geometry_msgs::msg::Vector3& vector)
53 {
55  p = Eigen::Vector3d(vector.x, vector.y, vector.z);
56  // transform has to be a valid isometry; the caller is responsible for the check
57  p = transform.linear() * p;
58 
59  geometry_msgs::msg::Vector3 result;
60  result.x = p.x();
61  result.y = p.y();
62  result.z = p.z();
63 
64  return result;
65 }
66 } // namespace
67 
68 DynamicsSolver::DynamicsSolver(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group_name,
69  const geometry_msgs::msg::Vector3& gravity_vector)
70 {
71  robot_model_ = robot_model;
72  joint_model_group_ = robot_model_->getJointModelGroup(group_name);
73  if (!joint_model_group_)
74  return;
75 
76  if (!joint_model_group_->isChain())
77  {
78  RCLCPP_ERROR(LOGGER, "Group '%s' is not a chain. Will not initialize dynamics solver", group_name.c_str());
79  joint_model_group_ = nullptr;
80  return;
81  }
82 
83  if (!joint_model_group_->getMimicJointModels().empty())
84  {
85  RCLCPP_ERROR(LOGGER, "Group '%s' has a mimic joint. Will not initialize dynamics solver", group_name.c_str());
86  joint_model_group_ = nullptr;
87  return;
88  }
89 
90  const moveit::core::JointModel* joint = joint_model_group_->getJointRoots()[0];
91  if (!joint->getParentLinkModel())
92  {
93  RCLCPP_ERROR(LOGGER, "Group '%s' does not have a parent link", group_name.c_str());
94  joint_model_group_ = nullptr;
95  return;
96  }
97 
98  base_name_ = joint->getParentLinkModel()->getName();
99 
100  tip_name_ = joint_model_group_->getLinkModelNames().back();
101  RCLCPP_DEBUG(LOGGER, "Base name: '%s', Tip name: '%s'", base_name_.c_str(), tip_name_.c_str());
102 
103  const urdf::ModelInterfaceSharedPtr urdf_model = robot_model_->getURDF();
104  const srdf::ModelConstSharedPtr srdf_model = robot_model_->getSRDF();
105  KDL::Tree tree;
106 
107  if (!kdl_parser::treeFromUrdfModel(*urdf_model, tree))
108  {
109  RCLCPP_ERROR(LOGGER, "Could not initialize tree object");
110  joint_model_group_ = nullptr;
111  return;
112  }
113  if (!tree.getChain(base_name_, tip_name_, kdl_chain_))
114  {
115  RCLCPP_ERROR(LOGGER, "Could not initialize chain object");
116  joint_model_group_ = nullptr;
117  return;
118  }
119  num_joints_ = kdl_chain_.getNrOfJoints();
120  num_segments_ = kdl_chain_.getNrOfSegments();
121 
122  state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
123  state_->setToDefaultValues();
124 
125  const std::vector<std::string>& joint_model_names = joint_model_group_->getJointModelNames();
126  for (const std::string& joint_model_name : joint_model_names)
127  {
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);
131  else
132  max_torques_.push_back(0.0);
133  }
134 
135  KDL::Vector gravity(gravity_vector.x, gravity_vector.y,
136  gravity_vector.z); // \todo Not sure if KDL expects the negative of this (Sachin)
137  gravity_ = gravity.Norm();
138  RCLCPP_DEBUG(LOGGER, "Gravity norm set to %f", gravity_);
139 
140  chain_id_solver_ = std::make_shared<KDL::ChainIdSolver_RNE>(kdl_chain_, gravity);
141 }
142 
143 bool DynamicsSolver::getTorques(const std::vector<double>& joint_angles, const std::vector<double>& joint_velocities,
144  const std::vector<double>& joint_accelerations,
145  const std::vector<geometry_msgs::msg::Wrench>& wrenches,
146  std::vector<double>& torques) const
147 {
148  if (!joint_model_group_)
149  {
150  RCLCPP_DEBUG(LOGGER, "Did not construct DynamicsSolver object properly. "
151  "Check error logs.");
152  return false;
153  }
154  if (joint_angles.size() != num_joints_)
155  {
156  RCLCPP_ERROR(LOGGER, "Joint angles vector should be size %d", num_joints_);
157  return false;
158  }
159  if (joint_velocities.size() != num_joints_)
160  {
161  RCLCPP_ERROR(LOGGER, "Joint velocities vector should be size %d", num_joints_);
162  return false;
163  }
164  if (joint_accelerations.size() != num_joints_)
165  {
166  RCLCPP_ERROR(LOGGER, "Joint accelerations vector should be size %d", num_joints_);
167  return false;
168  }
169  if (wrenches.size() != num_segments_)
170  {
171  RCLCPP_ERROR(LOGGER, "Wrenches vector should be size %d", num_segments_);
172  return false;
173  }
174  if (torques.size() != num_joints_)
175  {
176  RCLCPP_ERROR(LOGGER, "Torques vector should be size %d", num_joints_);
177  return false;
178  }
179 
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_);
183 
184  for (unsigned int i = 0; i < num_joints_; ++i)
185  {
186  kdl_angles(i) = joint_angles[i];
187  kdl_velocities(i) = joint_velocities[i];
188  kdl_accelerations(i) = joint_accelerations[i];
189  }
190 
191  for (unsigned int i = 0; i < num_segments_; ++i)
192  {
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;
196 
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;
200  }
201 
202  if (chain_id_solver_->CartToJnt(kdl_angles, kdl_velocities, kdl_accelerations, kdl_wrenches, kdl_torques) < 0)
203  {
204  RCLCPP_ERROR(LOGGER, "Something went wrong computing torques");
205  return false;
206  }
207 
208  for (unsigned int i = 0; i < num_joints_; ++i)
209  torques[i] = kdl_torques(i);
210 
211  return true;
212 }
213 
214 bool DynamicsSolver::getMaxPayload(const std::vector<double>& joint_angles, double& payload,
215  unsigned int& joint_saturated) const
216 {
217  if (!joint_model_group_)
218  {
219  RCLCPP_DEBUG(LOGGER, "Did not construct DynamicsSolver object properly. "
220  "Check error logs.");
221  return false;
222  }
223  if (joint_angles.size() != num_joints_)
224  {
225  RCLCPP_ERROR(LOGGER, "Joint angles vector should be size %d", num_joints_);
226  return false;
227  }
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);
230 
231  std::vector<geometry_msgs::msg::Wrench> wrenches(num_segments_);
232  if (!getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, zero_torques))
233  return false;
234 
235  for (unsigned int i = 0; i < num_joints_; ++i)
236  {
237  if (fabs(zero_torques[i]) >= max_torques_[i])
238  {
239  payload = 0.0;
240  joint_saturated = i;
241  return true;
242  }
243  }
244 
245  state_->setJointGroupPositions(joint_model_group_, joint_angles);
246  const Eigen::Isometry3d& base_frame = state_->getFrameTransform(base_name_); // valid isometry by contract
247  const Eigen::Isometry3d& tip_frame = state_->getFrameTransform(tip_name_); // valid isometry by contract
248  Eigen::Isometry3d transform = tip_frame.inverse() * base_frame; // valid isometry by construction
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);
252 
253  RCLCPP_DEBUG(LOGGER, "New wrench (local frame): %f %f %f", wrenches.back().force.x, wrenches.back().force.y,
254  wrenches.back().force.z);
255 
256  if (!getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, torques))
257  return false;
258 
259  double min_payload = std::numeric_limits<double>::max();
260  for (unsigned int i = 0; i < num_joints_; ++i)
261  {
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])); // because we set the payload to 1.0
265  RCLCPP_DEBUG(LOGGER, "Joint: %d, Actual Torque: %f, Max Allowed: %f, Gravity: %f", i, torques[i], max_torques_[i],
266  zero_torques[i]);
267  RCLCPP_DEBUG(LOGGER, "Joint: %d, Payload Allowed (N): %f", i, payload_joint);
268  if (payload_joint < min_payload)
269  {
270  min_payload = payload_joint;
271  joint_saturated = i;
272  }
273  }
274  payload = min_payload / gravity_;
275  RCLCPP_DEBUG(LOGGER, "Max payload (kg): %f", payload);
276  return true;
277 }
278 
279 bool DynamicsSolver::getPayloadTorques(const std::vector<double>& joint_angles, double payload,
280  std::vector<double>& joint_torques) const
281 {
282  if (!joint_model_group_)
283  {
284  RCLCPP_DEBUG(LOGGER, "Did not construct DynamicsSolver object properly. "
285  "Check error logs.");
286  return false;
287  }
288  if (joint_angles.size() != num_joints_)
289  {
290  RCLCPP_ERROR(LOGGER, "Joint angles vector should be size %d", num_joints_);
291  return false;
292  }
293  if (joint_torques.size() != num_joints_)
294  {
295  RCLCPP_ERROR(LOGGER, "Joint torques vector should be size %d", num_joints_);
296  return false;
297  }
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);
301 
302  const Eigen::Isometry3d& base_frame = state_->getFrameTransform(base_name_); // valid isometry by contract
303  const Eigen::Isometry3d& tip_frame = state_->getFrameTransform(tip_name_); // valid isometry by contract
304  Eigen::Isometry3d transform = tip_frame.inverse() * base_frame; // valid isometry by construction
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);
308 
309  RCLCPP_DEBUG(LOGGER, "New wrench (local frame): %f %f %f", wrenches.back().force.x, wrenches.back().force.y,
310  wrenches.back().force.z);
311 
312  return getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, joint_torques);
313 }
314 
315 const std::vector<double>& DynamicsSolver::getMaxTorques() const
316 {
317  return max_torques_;
318 }
319 
320 } // end of namespace dynamics_solver
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....
Definition: joint_model.h:117
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint,...
Definition: joint_model.h:162
const std::string & getName() const
The name of this link.
Definition: link_model.h:86
This namespace includes the dynamics_solver library.
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
p
Definition: pick.py:62