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