#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::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) 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::JointModelGroup * | joint_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_ |
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.
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.
urdf_model | The urdf model for the robot |
srdf_model | The srdf model for the robot |
group_name | The name of the group to compute stuff for |
Definition at line 96 of file dynamics_solver.cpp.
|
inline |
Definition at line 164 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)
joint_angles | The joint angles (desired joint configuration) this must have size = number of joints in the group |
payload | The computed maximum payload |
joint_saturated | The first saturated joint and the maximum payload |
Definition at line 243 of file dynamics_solver.cpp.
const std::vector< double > & dynamics_solver::DynamicsSolver::getMaxTorques | ( | ) | const |
Get maximum torques for this group.
Definition at line 344 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.
joint_angles | The joint angles (desired joint configuration) this must have size = number of joints in the group |
payload | The payload for which to compute torques (in kg) |
joint_torques | The resulting joint torques |
Definition at line 308 of file dynamics_solver.cpp.
|
inline |
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)
joint_angles | The joint angles (desired joint configuration) this must have size = number of joints in the group |
joint_velocities | The desired joint velocities this must have size = number of joints in the group |
joint_accelerations | The desired joint accelerations this must have size = number of joints in the group |
wrenches | External wrenches acting on the links of the robot this must have size = number of links in the group |
torques | Computed set of torques are filled in here this must have size = number of joints in the group |
Definition at line 173 of file dynamics_solver.cpp.
|
private |
Definition at line 178 of file dynamics_solver.h.
|
private |
Definition at line 170 of file dynamics_solver.h.
|
private |
Definition at line 182 of file dynamics_solver.h.
|
private |
Definition at line 174 of file dynamics_solver.h.
|
private |
Definition at line 171 of file dynamics_solver.h.
|
private |
Definition at line 180 of file dynamics_solver.h.
|
private |
Definition at line 179 of file dynamics_solver.h.
|
private |
Definition at line 179 of file dynamics_solver.h.
|
private |
Definition at line 173 of file dynamics_solver.h.
|
private |
Definition at line 176 of file dynamics_solver.h.
|
private |
Definition at line 178 of file dynamics_solver.h.