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 
39 // KDL
40 #include <kdl/jntarray.hpp>
42 #include <kdl/tree.hpp>
43 
44 namespace dynamics_solver
45 {
46 namespace
47 {
48 inline geometry_msgs::Vector3 transformVector(const Eigen::Isometry3d& transform, const geometry_msgs::Vector3& vector)
49 {
51  p = Eigen::Vector3d(vector.x, vector.y, vector.z);
52  // transform has to be a valid isometry; the caller is responsible for the check
53  p = transform.linear() * p;
54 
55  geometry_msgs::Vector3 result;
56  result.x = p.x();
57  result.y = p.y();
58  result.z = p.z();
59 
60  return result;
61 }
62 } // namespace
63 
64 DynamicsSolver::DynamicsSolver(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group_name,
65  const geometry_msgs::Vector3& gravity_vector)
66 {
68  joint_model_group_ = robot_model_->getJointModelGroup(group_name);
69  if (!joint_model_group_)
70  return;
71 
73  {
74  ROS_ERROR_NAMED("dynamics_solver", "Group '%s' is not a chain. Will not initialize dynamics solver",
75  group_name.c_str());
76  joint_model_group_ = nullptr;
77  return;
78  }
79 
81  {
82  ROS_ERROR_NAMED("dynamics_solver", "Group '%s' has a mimic joint. Will not initialize dynamics solver",
83  group_name.c_str());
84  joint_model_group_ = nullptr;
85  return;
86  }
87 
89  if (!joint->getParentLinkModel())
90  {
91  ROS_ERROR_NAMED("dynamics_solver", "Group '%s' does not have a parent link", group_name.c_str());
92  joint_model_group_ = nullptr;
93  return;
94  }
95 
97 
99  ROS_DEBUG_NAMED("dynamics_solver", "Base name: '%s', Tip name: '%s'", base_name_.c_str(), tip_name_.c_str());
100 
101  const urdf::ModelInterfaceSharedPtr urdf_model = robot_model_->getURDF();
102  const srdf::ModelConstSharedPtr srdf_model = robot_model_->getSRDF();
103  KDL::Tree tree;
104 
105  if (!kdl_parser::treeFromUrdfModel(*urdf_model, tree))
106  {
107  ROS_ERROR_NAMED("dynamics_solver", "Could not initialize tree object");
108  joint_model_group_ = nullptr;
109  return;
110  }
111  if (!tree.getChain(base_name_, tip_name_, kdl_chain_))
112  {
113  ROS_ERROR_NAMED("dynamics_solver", "Could not initialize chain object");
114  joint_model_group_ = nullptr;
115  return;
116  }
117  num_joints_ = kdl_chain_.getNrOfJoints();
118  num_segments_ = kdl_chain_.getNrOfSegments();
119 
120  state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
121  state_->setToDefaultValues();
122 
123  const std::vector<std::string>& joint_model_names = joint_model_group_->getJointModelNames();
124  for (const std::string& joint_model_name : joint_model_names)
125  {
126  const urdf::Joint* ujoint = urdf_model->getJoint(joint_model_name).get();
127  if (ujoint && ujoint->limits)
128  max_torques_.push_back(ujoint->limits->effort);
129  else
130  max_torques_.push_back(0.0);
131  }
132 
133  KDL::Vector gravity(gravity_vector.x, gravity_vector.y,
134  gravity_vector.z); // \todo Not sure if KDL expects the negative of this (Sachin)
135  gravity_ = gravity.Norm();
136  ROS_DEBUG_NAMED("dynamics_solver", "Gravity norm set to %f", gravity_);
137 
138  chain_id_solver_ = std::make_shared<KDL::ChainIdSolver_RNE>(kdl_chain_, gravity);
139 }
140 
141 bool DynamicsSolver::getTorques(const std::vector<double>& joint_angles, const std::vector<double>& joint_velocities,
142  const std::vector<double>& joint_accelerations,
143  const std::vector<geometry_msgs::Wrench>& wrenches, std::vector<double>& torques) const
144 {
145  if (!joint_model_group_)
146  {
147  ROS_DEBUG_NAMED("dynamics_solver", "Did not construct DynamicsSolver object properly. "
148  "Check error logs.");
149  return false;
150  }
151  if (joint_angles.size() != num_joints_)
152  {
153  ROS_ERROR_NAMED("dynamics_solver", "Joint angles vector should be size %d", num_joints_);
154  return false;
155  }
156  if (joint_velocities.size() != num_joints_)
157  {
158  ROS_ERROR_NAMED("dynamics_solver", "Joint velocities vector should be size %d", num_joints_);
159  return false;
160  }
161  if (joint_accelerations.size() != num_joints_)
162  {
163  ROS_ERROR_NAMED("dynamics_solver", "Joint accelerations vector should be size %d", num_joints_);
164  return false;
165  }
166  if (wrenches.size() != num_segments_)
167  {
168  ROS_ERROR_NAMED("dynamics_solver", "Wrenches vector should be size %d", num_segments_);
169  return false;
170  }
171  if (torques.size() != num_joints_)
172  {
173  ROS_ERROR_NAMED("dynamics_solver", "Torques vector should be size %d", num_joints_);
174  return false;
175  }
176 
177  KDL::JntArray kdl_angles(num_joints_), kdl_velocities(num_joints_), kdl_accelerations(num_joints_),
178  kdl_torques(num_joints_);
179  KDL::Wrenches kdl_wrenches(num_segments_);
180 
181  for (unsigned int i = 0; i < num_joints_; ++i)
182  {
183  kdl_angles(i) = joint_angles[i];
184  kdl_velocities(i) = joint_velocities[i];
185  kdl_accelerations(i) = joint_accelerations[i];
186  }
187 
188  for (unsigned int i = 0; i < num_segments_; ++i)
189  {
190  kdl_wrenches[i](0) = wrenches[i].force.x;
191  kdl_wrenches[i](1) = wrenches[i].force.y;
192  kdl_wrenches[i](2) = wrenches[i].force.z;
193 
194  kdl_wrenches[i](3) = wrenches[i].torque.x;
195  kdl_wrenches[i](4) = wrenches[i].torque.y;
196  kdl_wrenches[i](5) = wrenches[i].torque.z;
197  }
198 
199  if (chain_id_solver_->CartToJnt(kdl_angles, kdl_velocities, kdl_accelerations, kdl_wrenches, kdl_torques) < 0)
200  {
201  ROS_ERROR_NAMED("dynamics_solver", "Something went wrong computing torques");
202  return false;
203  }
204 
205  for (unsigned int i = 0; i < num_joints_; ++i)
206  torques[i] = kdl_torques(i);
207 
208  return true;
209 }
210 
211 bool DynamicsSolver::getMaxPayload(const std::vector<double>& joint_angles, double& payload,
212  unsigned int& joint_saturated) const
213 {
214  if (!joint_model_group_)
215  {
216  ROS_DEBUG_NAMED("dynamics_solver", "Did not construct DynamicsSolver object properly. "
217  "Check error logs.");
218  return false;
219  }
220  if (joint_angles.size() != num_joints_)
221  {
222  ROS_ERROR_NAMED("dynamics_solver", "Joint angles vector should be size %d", num_joints_);
223  return false;
224  }
225  std::vector<double> joint_velocities(num_joints_, 0.0), joint_accelerations(num_joints_, 0.0);
226  std::vector<double> torques(num_joints_, 0.0), zero_torques(num_joints_, 0.0);
227 
228  std::vector<geometry_msgs::Wrench> wrenches(num_segments_);
229  if (!getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, zero_torques))
230  return false;
231 
232  for (unsigned int i = 0; i < num_joints_; ++i)
233  {
234  if (fabs(zero_torques[i]) >= max_torques_[i])
235  {
236  payload = 0.0;
237  joint_saturated = i;
238  return true;
239  }
240  }
241 
242  state_->setJointGroupPositions(joint_model_group_, joint_angles);
243  const Eigen::Isometry3d& base_frame = state_->getFrameTransform(base_name_); // valid isometry by contract
244  const Eigen::Isometry3d& tip_frame = state_->getFrameTransform(tip_name_); // valid isometry by contract
245  Eigen::Isometry3d transform = tip_frame.inverse() * base_frame; // valid isometry by construction
246  wrenches.back().force.z = 1.0;
247  wrenches.back().force = transformVector(transform, wrenches.back().force);
248  wrenches.back().torque = transformVector(transform, wrenches.back().torque);
249 
250  ROS_DEBUG_NAMED("dynamics_solver", "New wrench (local frame): %f %f %f", wrenches.back().force.x,
251  wrenches.back().force.y, wrenches.back().force.z);
252 
253  if (!getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, torques))
254  return false;
255 
256  double min_payload = std::numeric_limits<double>::max();
257  for (unsigned int i = 0; i < num_joints_; ++i)
258  {
259  double payload_joint = std::max<double>((max_torques_[i] - zero_torques[i]) / (torques[i] - zero_torques[i]),
260  (-max_torques_[i] - zero_torques[i]) /
261  (torques[i] - zero_torques[i])); // because we set the payload to 1.0
262  ROS_DEBUG_NAMED("dynamics_solver", "Joint: %d, Actual Torque: %f, Max Allowed: %f, Gravity: %f", i, torques[i],
263  max_torques_[i], zero_torques[i]);
264  ROS_DEBUG_NAMED("dynamics_solver", "Joint: %d, Payload Allowed (N): %f", i, payload_joint);
265  if (payload_joint < min_payload)
266  {
267  min_payload = payload_joint;
268  joint_saturated = i;
269  }
270  }
271  payload = min_payload / gravity_;
272  ROS_DEBUG_NAMED("dynamics_solver", "Max payload (kg): %f", payload);
273  return true;
274 }
275 
276 bool DynamicsSolver::getPayloadTorques(const std::vector<double>& joint_angles, double payload,
277  std::vector<double>& joint_torques) const
278 {
279  if (!joint_model_group_)
280  {
281  ROS_DEBUG_NAMED("dynamics_solver", "Did not construct DynamicsSolver object properly. "
282  "Check error logs.");
283  return false;
284  }
285  if (joint_angles.size() != num_joints_)
286  {
287  ROS_ERROR_NAMED("dynamics_solver", "Joint angles vector should be size %d", num_joints_);
288  return false;
289  }
290  if (joint_torques.size() != num_joints_)
291  {
292  ROS_ERROR_NAMED("dynamics_solver", "Joint torques vector should be size %d", num_joints_);
293  return false;
294  }
295  std::vector<double> joint_velocities(num_joints_, 0.0), joint_accelerations(num_joints_, 0.0);
296  std::vector<geometry_msgs::Wrench> wrenches(num_segments_);
297  state_->setJointGroupPositions(joint_model_group_, joint_angles);
298 
299  const Eigen::Isometry3d& base_frame = state_->getFrameTransform(base_name_); // valid isometry by contract
300  const Eigen::Isometry3d& tip_frame = state_->getFrameTransform(tip_name_); // valid isometry by contract
301  Eigen::Isometry3d transform = tip_frame.inverse() * base_frame; // valid isometry by construction
302  wrenches.back().force.z = payload * gravity_;
303  wrenches.back().force = transformVector(transform, wrenches.back().force);
304  wrenches.back().torque = transformVector(transform, wrenches.back().torque);
305 
306  ROS_DEBUG_NAMED("dynamics_solver", "New wrench (local frame): %f %f %f", wrenches.back().force.x,
307  wrenches.back().force.y, wrenches.back().force.z);
308 
309  return getTorques(joint_angles, joint_velocities, joint_accelerations, wrenches, joint_torques);
310 }
311 
312 const std::vector<double>& DynamicsSolver::getMaxTorques() const
313 {
314  return max_torques_;
315 }
316 
317 } // end of namespace dynamics_solver
moveit::core
Core components of MoveIt.
Definition: kinematics_base.h:83
moveit::core::JointModelGroup::getJointRoots
const std::vector< const JointModel * > & getJointRoots() const
Unlike a complete kinematic model, a group may contain disconnected parts of the kinematic tree – a s...
Definition: joint_model_group.h:266
dynamics_solver::DynamicsSolver::getMaxPayload
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...
Definition: dynamics_solver.cpp:243
dynamics_solver::DynamicsSolver::getTorques
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::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 ...
Definition: dynamics_solver.cpp:173
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit::core::JointModelGroup::getMimicJointModels
const std::vector< const JointModel * > & getMimicJointModels() const
Get the mimic joints that are part of this group.
Definition: joint_model_group.h:241
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
kdl_parser::treeFromUrdfModel
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
dynamics_solver::DynamicsSolver::tip_name_
std::string tip_name_
Definition: dynamics_solver.h:178
moveit::core::JointModel::getParentLinkModel
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:213
dynamics_solver::DynamicsSolver::max_torques_
std::vector< double > max_torques_
Definition: dynamics_solver.h:180
dynamics_solver::DynamicsSolver::gravity_
double gravity_
Definition: dynamics_solver.h:182
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
moveit::core::JointModelGroup::getJointModelNames
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...
Definition: joint_model_group.h:216
srdf::ModelConstSharedPtr
std::shared_ptr< const Model > ModelConstSharedPtr
dynamics_solver
This namespace includes the dynamics_solver library.
Definition: dynamics_solver.h:50
kdl_parser.hpp
moveit::core::JointModelGroup::getLinkModelNames
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
Definition: joint_model_group.h:284
dynamics_solver::DynamicsSolver::chain_id_solver_
std::shared_ptr< KDL::ChainIdSolver_RNE > chain_id_solver_
Definition: dynamics_solver.h:170
dynamics_solver::DynamicsSolver::state_
moveit::core::RobotStatePtr state_
Definition: dynamics_solver.h:176
dynamics_solver::DynamicsSolver::getPayloadTorques
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...
Definition: dynamics_solver.cpp:308
dynamics_solver::DynamicsSolver::kdl_chain_
KDL::Chain kdl_chain_
Definition: dynamics_solver.h:171
moveit::core::JointModelGroup::isChain
bool isChain() const
Check if this group is a linear chain.
Definition: joint_model_group.h:506
dynamics_solver::DynamicsSolver::base_name_
std::string base_name_
Definition: dynamics_solver.h:178
dynamics_solver::DynamicsSolver::robot_model_
moveit::core::RobotModelConstPtr robot_model_
Definition: dynamics_solver.h:173
dynamics_solver::DynamicsSolver::getMaxTorques
const std::vector< double > & getMaxTorques() const
Get maximum torques for this group.
Definition: dynamics_solver.cpp:344
moveit::core::LinkModel::getName
const std::string & getName() const
The name of this link.
Definition: link_model.h:80
dynamics_solver::DynamicsSolver::joint_model_group_
const moveit::core::JointModelGroup * joint_model_group_
Definition: dynamics_solver.h:174
dynamics_solver.h
dynamics_solver::DynamicsSolver::num_segments_
unsigned int num_segments_
Definition: dynamics_solver.h:179
dynamics_solver::DynamicsSolver::num_joints_
unsigned int num_joints_
Definition: dynamics_solver.h:179
moveit::core::JointModel
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:173
dynamics_solver::DynamicsSolver::DynamicsSolver
DynamicsSolver(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const geometry_msgs::Vector3 &gravity_vector)
Initialize the dynamics solver.
Definition: dynamics_solver.cpp:96
fcl::Vector3d
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14