moveit2
The MoveIt Motion Planning Framework for ROS 2.
Namespaces | Functions
command.hpp File Reference
#include <moveit_servo/utils/common.hpp>
#include <moveit/kinematics_base/kinematics_base.h>
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <rclcpp/rclcpp.hpp>
#include <tf2_eigen/tf2_eigen.hpp>
Include dependency graph for command.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 moveit_servo
 

Functions

JointDeltaResult moveit_servo::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. More...
 
JointDeltaResult moveit_servo::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. More...
 
JointDeltaResult moveit_servo::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. More...
 
JointDeltaResult moveit_servo::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. More...