Go to the documentation of this file.
40 #include <kdl/chain.hpp>
41 #include <kdl/chainidsolver_recursive_newton_euler.hpp>
44 #include <geometry_msgs/Vector3.h>
45 #include <geometry_msgs/Wrench.h>
70 const geometry_msgs::Vector3& gravity_vector);
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;
102 bool getMaxPayload(
const std::vector<double>& joint_angles,
double& payload,
unsigned int& joint_saturated)
const;
115 std::vector<double>& joint_torques)
const;
127 const moveit::core::RobotModelConstPtr&
getRobotModel()
const
144 moveit::core::RobotStatePtr
state_;
Core components of MoveIt.
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...
MOVEIT_CLASS_FORWARD(DynamicsSolver)
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 ...
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the kinematic model.
std::vector< double > max_torques_
This namespace includes the dynamics_solver library.
std::shared_ptr< KDL::ChainIdSolver_RNE > chain_id_solver_
moveit::core::RobotStatePtr state_
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...
const moveit::core::JointModelGroup * getGroup() const
moveit::core::RobotModelConstPtr robot_model_
const std::vector< double > & getMaxTorques() const
Get maximum torques for this group.
const moveit::core::JointModelGroup * joint_model_group_
unsigned int num_segments_
DynamicsSolver(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const geometry_msgs::Vector3 &gravity_vector)
Initialize the dynamics solver.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14