40 #include <kdl/chain.hpp>
41 #include <kdl/chainidsolver_recursive_newton_euler.hpp>
44 #include <geometry_msgs/msg/vector3.hpp>
45 #include <geometry_msgs/msg/wrench.hpp>
68 DynamicsSolver(
const moveit::core::RobotModelConstPtr& robot_model,
const std::string& group_name,
69 const geometry_msgs::msg::Vector3& gravity_vector);
86 bool getTorques(
const std::vector<double>& joint_angles,
const std::vector<double>& joint_velocities,
87 const std::vector<double>& joint_accelerations,
88 const std::vector<geometry_msgs::msg::Wrench>& wrenches, std::vector<double>& torques)
const;
101 bool getMaxPayload(
const std::vector<double>& joint_angles,
double& payload,
unsigned int& joint_saturated)
const;
114 std::vector<double>& joint_torques)
const;
133 return joint_model_group_;
137 std::shared_ptr<KDL::ChainIdSolver_RNE> chain_id_solver_;
138 KDL::Chain kdl_chain_;
140 moveit::core::RobotModelConstPtr robot_model_;
143 moveit::core::RobotStatePtr state_;
145 std::string base_name_, tip_name_;
146 unsigned int num_joints_, num_segments_;
147 std::vector<double> max_torques_;
const std::vector< double > & getMaxTorques() const
Get maximum torques for this group.
DynamicsSolver(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const geometry_msgs::msg::Vector3 &gravity_vector)
Initialize the dynamics solver.
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 t...
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::msg::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.
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...
This namespace includes the dynamics_solver library.
MOVEIT_CLASS_FORWARD(DynamicsSolver)