Public Member Functions | Private Attributes | List of all members
dynamics_solver::DynamicsSolver Class Reference

#include <dynamics_solver.h>

Public Member Functions

 DynamicsSolver (const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const geometry_msgs::Vector3 &gravity_vector)
 Initialize the dynamics solver. More...
 
const moveit::core::JointModelGroupgetGroup () const
 
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 the weight is attached to the origin of the last link of this group. (The order of joint_angles vector is the same as the order of joints for this group in the RobotModel) More...
 
const std::vector< double > & getMaxTorques () const
 Get maximum torques for this group. More...
 
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 hold when the weight is attached to the origin of the last link of this group. More...
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 Get the kinematic model. More...
 
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 in the RobotModel) More...
 

Private Attributes

std::string base_name_
 
std::shared_ptr< KDL::ChainIdSolver_RNE > chain_id_solver_
 
double gravity_
 
const moveit::core::JointModelGroupjoint_model_group_
 
KDL::Chain kdl_chain_
 
std::vector< double > max_torques_
 
unsigned int num_joints_
 
unsigned int num_segments_
 
moveit::core::RobotModelConstPtr robot_model_
 
moveit::core::RobotStatePtr state_
 
std::string tip_name_
 

Detailed Description

This solver currently computes the required torques given a joint configuration, velocities, accelerations and external wrenches acting on the links of a robot

Definition at line 91 of file dynamics_solver.h.

Constructor & Destructor Documentation

◆ DynamicsSolver()

dynamics_solver::DynamicsSolver::DynamicsSolver ( const moveit::core::RobotModelConstPtr &  robot_model,
const std::string &  group_name,
const geometry_msgs::Vector3 gravity_vector 
)

Initialize the dynamics solver.

Parameters
urdf_modelThe urdf model for the robot
srdf_modelThe srdf model for the robot
group_nameThe name of the group to compute stuff for
Returns
False if initialization failed

Definition at line 96 of file dynamics_solver.cpp.

Member Function Documentation

◆ getGroup()

const moveit::core::JointModelGroup* dynamics_solver::DynamicsSolver::getGroup ( ) const
inline

Definition at line 164 of file dynamics_solver.h.

◆ getMaxPayload()

bool dynamics_solver::DynamicsSolver::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 the weight is attached to the origin of the last link of this group. (The order of joint_angles vector is the same as the order of joints for this group in the RobotModel)

Parameters
joint_anglesThe joint angles (desired joint configuration) this must have size = number of joints in the group
payloadThe computed maximum payload
joint_saturatedThe first saturated joint and the maximum payload
Returns
False if the input set of joint angles is of the wrong size

Definition at line 243 of file dynamics_solver.cpp.

◆ getMaxTorques()

const std::vector< double > & dynamics_solver::DynamicsSolver::getMaxTorques ( ) const

Get maximum torques for this group.

Returns
Vector of max torques

Definition at line 344 of file dynamics_solver.cpp.

◆ getPayloadTorques()

bool dynamics_solver::DynamicsSolver::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 hold when the weight is attached to the origin of the last link of this group.

Parameters
joint_anglesThe joint angles (desired joint configuration) this must have size = number of joints in the group
payloadThe payload for which to compute torques (in kg)
joint_torquesThe resulting joint torques
Returns
False if the input vectors are of the wrong size

Definition at line 308 of file dynamics_solver.cpp.

◆ getRobotModel()

const moveit::core::RobotModelConstPtr& dynamics_solver::DynamicsSolver::getRobotModel ( ) const
inline

Get the kinematic model.

Returns
kinematic model

Definition at line 159 of file dynamics_solver.h.

◆ getTorques()

bool dynamics_solver::DynamicsSolver::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 in the RobotModel)

Parameters
joint_anglesThe joint angles (desired joint configuration) this must have size = number of joints in the group
joint_velocitiesThe desired joint velocities this must have size = number of joints in the group
joint_accelerationsThe desired joint accelerations this must have size = number of joints in the group
wrenchesExternal wrenches acting on the links of the robot this must have size = number of links in the group
torquesComputed set of torques are filled in here this must have size = number of joints in the group
Returns
False if any of the input vectors are of the wrong size

Definition at line 173 of file dynamics_solver.cpp.

Member Data Documentation

◆ base_name_

std::string dynamics_solver::DynamicsSolver::base_name_
private

Definition at line 178 of file dynamics_solver.h.

◆ chain_id_solver_

std::shared_ptr<KDL::ChainIdSolver_RNE> dynamics_solver::DynamicsSolver::chain_id_solver_
private

Definition at line 170 of file dynamics_solver.h.

◆ gravity_

double dynamics_solver::DynamicsSolver::gravity_
private

Definition at line 182 of file dynamics_solver.h.

◆ joint_model_group_

const moveit::core::JointModelGroup* dynamics_solver::DynamicsSolver::joint_model_group_
private

Definition at line 174 of file dynamics_solver.h.

◆ kdl_chain_

KDL::Chain dynamics_solver::DynamicsSolver::kdl_chain_
private

Definition at line 171 of file dynamics_solver.h.

◆ max_torques_

std::vector<double> dynamics_solver::DynamicsSolver::max_torques_
private

Definition at line 180 of file dynamics_solver.h.

◆ num_joints_

unsigned int dynamics_solver::DynamicsSolver::num_joints_
private

Definition at line 179 of file dynamics_solver.h.

◆ num_segments_

unsigned int dynamics_solver::DynamicsSolver::num_segments_
private

Definition at line 179 of file dynamics_solver.h.

◆ robot_model_

moveit::core::RobotModelConstPtr dynamics_solver::DynamicsSolver::robot_model_
private

Definition at line 173 of file dynamics_solver.h.

◆ state_

moveit::core::RobotStatePtr dynamics_solver::DynamicsSolver::state_
private

Definition at line 176 of file dynamics_solver.h.

◆ tip_name_

std::string dynamics_solver::DynamicsSolver::tip_name_
private

Definition at line 178 of file dynamics_solver.h.


The documentation for this class was generated from the following files:


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Mar 3 2024 03:23:36