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/Vector3.h>
45 #include <geometry_msgs/Wrench.h>
46 
47 #include <memory>
48 
50 namespace dynamics_solver
51 {
52 MOVEIT_CLASS_FORWARD(DynamicsSolver); // Defines DynamicsSolverPtr, ConstPtr, WeakPtr... etc
53 
59 class DynamicsSolver
60 {
61 public:
69  DynamicsSolver(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group_name,
70  const geometry_msgs::Vector3& gravity_vector);
71 
87  bool getTorques(const std::vector<double>& joint_angles, const std::vector<double>& joint_velocities,
88  const std::vector<double>& joint_accelerations, const std::vector<geometry_msgs::Wrench>& wrenches,
89  std::vector<double>& torques) const;
90 
102  bool getMaxPayload(const std::vector<double>& joint_angles, double& payload, unsigned int& joint_saturated) const;
103 
114  bool getPayloadTorques(const std::vector<double>& joint_angles, double payload,
115  std::vector<double>& joint_torques) const;
116 
121  const std::vector<double>& getMaxTorques() const;
122 
127  const moveit::core::RobotModelConstPtr& getRobotModel() const
128  {
129  return robot_model_;
130  }
131 
133  {
134  return joint_model_group_;
135  }
136 
137 private:
138  std::shared_ptr<KDL::ChainIdSolver_RNE> chain_id_solver_; // KDL chain inverse dynamics
139  KDL::Chain kdl_chain_; // KDL chain
140 
141  moveit::core::RobotModelConstPtr robot_model_;
143 
144  moveit::core::RobotStatePtr state_; // robot state
145 
146  std::string base_name_, tip_name_; // base name, tip name
147  unsigned int num_joints_, num_segments_; // number of joints in group, number of segments in group
148  std::vector<double> max_torques_; // vector of max torques
149 
150  double gravity_; // Norm of the gravity vector passed in initialize()
151 };
152 } // namespace dynamics_solver
moveit::core
Core components of MoveIt.
Definition: kinematics_base.h:83
dynamics_solver::DynamicsSolver
Definition: dynamics_solver.h:91
moveit::core::JointModelGroup
Definition: joint_model_group.h:134
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::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(DynamicsSolver)
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
dynamics_solver::DynamicsSolver::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the kinematic model.
Definition: dynamics_solver.h:159
dynamics_solver::DynamicsSolver::tip_name_
std::string tip_name_
Definition: dynamics_solver.h:178
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
dynamics_solver
This namespace includes the dynamics_solver library.
Definition: dynamics_solver.h:50
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
dynamics_solver::DynamicsSolver::base_name_
std::string base_name_
Definition: dynamics_solver.h:178
dynamics_solver::DynamicsSolver::getGroup
const moveit::core::JointModelGroup * getGroup() const
Definition: dynamics_solver.h:164
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
dynamics_solver::DynamicsSolver::joint_model_group_
const moveit::core::JointModelGroup * joint_model_group_
Definition: dynamics_solver.h:174
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
robot_state.h
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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Feb 21 2024 03:25:09