37 #ifndef MOVEIT_DYNAMICS_SOLVER_DYNAMICS_SOLVER_ 38 #define MOVEIT_DYNAMICS_SOLVER_DYNAMICS_SOLVER_ 41 #include <kdl/chain.hpp> 42 #include <kdl/chainidsolver_recursive_newton_euler.hpp> 45 #include <geometry_msgs/Vector3.h> 46 #include <geometry_msgs/Wrench.h> 71 const geometry_msgs::Vector3& gravity_vector);
88 bool getTorques(
const std::vector<double>& joint_angles,
const std::vector<double>& joint_velocities,
89 const std::vector<double>& joint_accelerations,
const std::vector<geometry_msgs::Wrench>& wrenches,
90 std::vector<double>& torques)
const;
103 bool getMaxPayload(
const std::vector<double>& joint_angles,
double& payload,
unsigned int& joint_saturated)
const;
116 std::vector<double>& joint_torques)
const;
const robot_model::JointModelGroup * getGroup() const
Core components of MoveIt!
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...
std::shared_ptr< KDL::ChainIdSolver_RNE > chain_id_solver_
robot_model::RobotModelConstPtr robot_model_
unsigned int num_segments_
const std::vector< double > & getMaxTorques() const
Get maximum torques for this group.
This namespace includes the dynamics_solver library.
MOVEIT_CLASS_FORWARD(DynamicsSolver)
robot_state::RobotStatePtr state_
const robot_model::RobotModelConstPtr & getRobotModel() const
Get the kinematic model.
const robot_model::JointModelGroup * joint_model_group_
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 ...
std::vector< double > max_torques_
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...
DynamicsSolver(const robot_model::RobotModelConstPtr &robot_model, const std::string &group_name, const geometry_msgs::Vector3 &gravity_vector)
Initialize the dynamics solver.