moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
dynamics_solver.h
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
37#pragma once
38
39// KDL
40#include <kdl/chain.hpp>
41#include <kdl/chainidsolver_recursive_newton_euler.hpp>
42
44#include <geometry_msgs/msg/vector3.hpp>
45#include <geometry_msgs/msg/wrench.hpp>
46#include <memory>
47
50{
51MOVEIT_CLASS_FORWARD(DynamicsSolver); // Defines DynamicsSolverPtr, ConstPtr, WeakPtr... etc
52
59{
60public:
68 DynamicsSolver(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group_name,
69 const geometry_msgs::msg::Vector3& gravity_vector);
70
86 bool getTorques(const std::vector<double>& joint_angles, const std::vector<double>& joint_velocities,
87 const std::vector<double>& joint_accelerations,
88 const std::vector<geometry_msgs::msg::Wrench>& wrenches, std::vector<double>& torques) const;
89
101 bool getMaxPayload(const std::vector<double>& joint_angles, double& payload, unsigned int& joint_saturated) const;
102
113 bool getPayloadTorques(const std::vector<double>& joint_angles, double payload,
114 std::vector<double>& joint_torques) const;
115
120 const std::vector<double>& getMaxTorques() const;
121
126 const moveit::core::RobotModelConstPtr& getRobotModel() const
127 {
128 return robot_model_;
129 }
130
132 {
133 return joint_model_group_;
134 }
135
136private:
137 std::shared_ptr<KDL::ChainIdSolver_RNE> chain_id_solver_; // KDL chain inverse dynamics
138 KDL::Chain kdl_chain_; // KDL chain
139
140 moveit::core::RobotModelConstPtr robot_model_;
141 const moveit::core::JointModelGroup* joint_model_group_;
142
143 moveit::core::RobotStatePtr state_; // robot state
144
145 std::string base_name_, tip_name_; // base name, tip name
146 unsigned int num_joints_, num_segments_; // number of joints in group, number of segments in group
147 std::vector<double> max_torques_; // vector of max torques
148
149 double gravity_; // Norm of the gravity vector passed in initialize()
150};
151} // namespace dynamics_solver
#define MOVEIT_CLASS_FORWARD(C)
const moveit::core::JointModelGroup * getGroup() const
const std::vector< double > & getMaxTorques() const
Get maximum torques for this group.
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 ...
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the kinematic model.
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...
This namespace includes the dynamics_solver library.