47#include <rclcpp/rclcpp.hpp>
48#include <tf2_eigen/tf2_eigen.hpp>
62 const servo::Params& servo_params,
75 const servo::Params& servo_params,
const std::string& planning_frame,
89 const servo::Params& servo_params,
const std::string& planning_frame,
90 const std::string& ee_frame,
102 const moveit::core::RobotStatePtr& robot_state,
const servo::Params& servo_params,
JointDeltaResult jointDeltaFromTwist(const TwistCommand &command, const moveit::core::RobotStatePtr &robot_state, const servo::Params &servo_params, const std::string &planning_frame, const JointNameToMoveGroupIndexMap &joint_name_group_index_map)
Compute the change in joint position for the given twist command.
JointDeltaResult jointDeltaFromJointJog(const JointJogCommand &command, const moveit::core::RobotStatePtr &robot_state, const servo::Params &servo_params, const JointNameToMoveGroupIndexMap &joint_name_group_index_map)
Compute the change in joint position for the given joint jog command.
JointDeltaResult jointDeltaFromIK(const Eigen::VectorXd &cartesian_position_delta, const moveit::core::RobotStatePtr &robot_state, const servo::Params &servo_params, const JointNameToMoveGroupIndexMap &joint_name_group_index_map)
Computes the required change in joint angles for given Cartesian change, using the robot's IK solver.
std::pair< StatusCode, Eigen::VectorXd > JointDeltaResult
JointDeltaResult jointDeltaFromPose(const PoseCommand &command, const moveit::core::RobotStatePtr &robot_state, const servo::Params &servo_params, const std::string &planning_frame, const std::string &ee_frame, const JointNameToMoveGroupIndexMap &joint_name_group_index_map)
Compute the change in joint position for the given pose command.
std::unordered_map< std::string, std::size_t > JointNameToMoveGroupIndexMap