Public Member Functions | Private Attributes
dynamics_solver::DynamicsSolver Class Reference

#include <dynamics_solver.h>

List of all members.

Public Member Functions

 DynamicsSolver (const robot_model::RobotModelConstPtr &robot_model, const std::string &group_name, const geometry_msgs::Vector3 &gravity_vector)
 Initialize the dynamics solver.
const
robot_model::JointModelGroup
getGroup () 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)
const std::vector< double > & getMaxTorques () const
 Get maximum torques 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 hold when the weight is attached to the origin of the last link of this group.
const
robot_model::RobotModelConstPtr & 
getRobotModel () const
 Get the kinematic model.
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)

Private Attributes

std::string base_name_
boost::shared_ptr
< KDL::ChainIdSolver_RNE
chain_id_solver_
double gravity_
const
robot_model::JointModelGroup
joint_model_group_
KDL::Chain kdl_chain_
std::vector< double > max_torques_
unsigned int num_joints_
unsigned int num_segments_
robot_model::RobotModelConstPtr robot_model_
robot_state::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 57 of file dynamics_solver.h.


Constructor & Destructor Documentation

dynamics_solver::DynamicsSolver::DynamicsSolver ( const robot_model::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 69 of file dynamics_solver.cpp.


Member Function Documentation

Definition at line 137 of file dynamics_solver.h.

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 214 of file dynamics_solver.cpp.

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

Get maximum torques for this group.

Returns:
Vector of max torques

Definition at line 312 of file dynamics_solver.cpp.

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 275 of file dynamics_solver.cpp.

const robot_model::RobotModelConstPtr& dynamics_solver::DynamicsSolver::getRobotModel ( ) const [inline]

Get the kinematic model.

Returns:
kinematic model

Definition at line 132 of file dynamics_solver.h.

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 144 of file dynamics_solver.cpp.


Member Data Documentation

Definition at line 152 of file dynamics_solver.h.

Definition at line 144 of file dynamics_solver.h.

Definition at line 156 of file dynamics_solver.h.

Definition at line 148 of file dynamics_solver.h.

Definition at line 145 of file dynamics_solver.h.

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

Definition at line 154 of file dynamics_solver.h.

Definition at line 153 of file dynamics_solver.h.

Definition at line 153 of file dynamics_solver.h.

robot_model::RobotModelConstPtr dynamics_solver::DynamicsSolver::robot_model_ [private]

Definition at line 147 of file dynamics_solver.h.

robot_state::RobotStatePtr dynamics_solver::DynamicsSolver::state_ [private]

Definition at line 150 of file dynamics_solver.h.

Definition at line 152 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 Thu Aug 27 2015 13:58:53