|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <atomic>#include <control_toolbox/pid.hpp>#include <moveit_servo/make_shared_from_pool.h>#include <moveit_servo/servo_parameters.h>#include <moveit_servo/servo.h>#include <optional>#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>#include <tf2_ros/transform_listener.h>#include <rclcpp/rclcpp.hpp>Go to the source code of this file.
Classes | |
| struct | moveit_servo::PIDConfig |
| class | moveit_servo::PoseTracking |
Namespaces | |
| moveit_servo | |
Typedefs | |
| using | moveit_servo::PoseTrackingPtr = std::shared_ptr< PoseTracking > |
Enumerations | |
| enum class | moveit_servo::PoseTrackingStatusCode : int8_t { moveit_servo::INVALID = -1 , moveit_servo::SUCCESS = 0 , moveit_servo::NO_RECENT_TARGET_POSE = 1 , moveit_servo::NO_RECENT_END_EFFECTOR_POSE = 2 , moveit_servo::STOP_REQUESTED = 3 } |
Functions | |
| const std::unordered_map< PoseTrackingStatusCode, std::string > | moveit_servo::POSE_TRACKING_STATUS_CODE_MAP ({ { PoseTrackingStatusCode::INVALID, "Invalid" }, { PoseTrackingStatusCode::SUCCESS, "Success" }, { PoseTrackingStatusCode::NO_RECENT_TARGET_POSE, "No recent target pose" }, { PoseTrackingStatusCode::NO_RECENT_END_EFFECTOR_POSE, "No recent end effector pose" }, { PoseTrackingStatusCode::STOP_REQUESTED, "Stop requested" } }) |