moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <string>
#include <tf2_eigen/tf2_eigen.hpp>
#include <unordered_map>
Go to the source code of this file.
Classes | |
struct | moveit_servo::JointJogCommand |
struct | moveit_servo::TwistCommand |
struct | moveit_servo::PoseCommand |
struct | moveit_servo::KinematicState |
Namespaces | |
namespace | moveit_servo |
Typedefs | |
typedef std::pair< StatusCode, Eigen::VectorXd > | moveit_servo::JointDeltaResult |
typedef std::variant< JointJogCommand, TwistCommand, PoseCommand > | moveit_servo::ServoInput |
typedef std::unordered_map< std::string, std::size_t > | moveit_servo::JointNameToMoveGroupIndexMap |
Enumerations | |
enum class | moveit_servo::StatusCode : int8_t { moveit_servo::INVALID = -1 , moveit_servo::NO_WARNING = 0 , moveit_servo::DECELERATE_FOR_APPROACHING_SINGULARITY = 1 , moveit_servo::HALT_FOR_SINGULARITY = 2 , moveit_servo::DECELERATE_FOR_LEAVING_SINGULARITY = 3 , moveit_servo::DECELERATE_FOR_COLLISION = 4 , moveit_servo::HALT_FOR_COLLISION = 5 , moveit_servo::JOINT_BOUND = 6 } |
enum class | moveit_servo::CommandType : int8_t { moveit_servo::JOINT_JOG = 0 , moveit_servo::TWIST = 1 , moveit_servo::POSE = 2 , moveit_servo::MIN = JOINT_JOG , moveit_servo::MAX = POSE } |
Functions | |
const std::unordered_map< StatusCode, std::string > | moveit_servo::SERVO_STATUS_CODE_MAP ({ { StatusCode::INVALID, "Invalid" }, { StatusCode::NO_WARNING, "No warnings" }, { StatusCode::DECELERATE_FOR_APPROACHING_SINGULARITY, "Moving closer to a singularity, decelerating" }, { StatusCode::HALT_FOR_SINGULARITY, "Very close to a singularity, emergency stop" }, { StatusCode::DECELERATE_FOR_LEAVING_SINGULARITY, "Moving away from a singularity, decelerating" }, { StatusCode::DECELERATE_FOR_COLLISION, "Close to a collision, decelerating" }, { StatusCode::HALT_FOR_COLLISION, "Collision detected, emergency stop" }, { StatusCode::JOINT_BOUND, "Close to a joint bound (position or velocity), halting" } }) |