|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Specification of options to use when constructing the MoveItCpp class. More...
#include <moveit_cpp.hpp>
Public Member Functions | |
| PlanningSceneMonitorOptions () | |
| void | load (const rclcpp::Node::SharedPtr &node) |
Public Attributes | |
| std::string | name |
| std::string | robot_description |
| const std::string | joint_state_topic |
| const std::string | attached_collision_object_topic |
| const std::string | monitored_planning_scene_topic |
| const std::string | publish_planning_scene_topic |
| double | wait_for_initial_state_timeout |
Specification of options to use when constructing the MoveItCpp class.
Definition at line 65 of file moveit_cpp.hpp.
|
inline |
Definition at line 67 of file moveit_cpp.hpp.
|
inline |
| const std::string moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::attached_collision_object_topic |
Definition at line 86 of file moveit_cpp.hpp.
| const std::string moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::joint_state_topic |
Definition at line 85 of file moveit_cpp.hpp.
| const std::string moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::monitored_planning_scene_topic |
Definition at line 87 of file moveit_cpp.hpp.
| std::string moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::name |
Definition at line 83 of file moveit_cpp.hpp.
| const std::string moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::publish_planning_scene_topic |
Definition at line 88 of file moveit_cpp.hpp.
| std::string moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::robot_description |
Definition at line 84 of file moveit_cpp.hpp.
| double moveit_cpp::MoveItCpp::PlanningSceneMonitorOptions::wait_for_initial_state_timeout |
Definition at line 89 of file moveit_cpp.hpp.