|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <moveit_cpp.hpp>
Classes | |
| struct | Options |
| Parameter container for initializing MoveItCpp. More... | |
| struct | PlanningPipelineOptions |
| struct contains the the variables used for loading the planning pipeline More... | |
| struct | PlanningSceneMonitorOptions |
| Specification of options to use when constructing the MoveItCpp class. More... | |
Public Member Functions | |
| MoveItCpp (const rclcpp::Node::SharedPtr &node) | |
| Constructor. | |
| MoveItCpp (const rclcpp::Node::SharedPtr &node, const Options &options) | |
| MoveItCpp (const MoveItCpp &)=delete | |
| This class owns unique resources (e.g. action clients, threads) and its not very meaningful to copy. Pass by references, move it, or simply create multiple instances where required. | |
| MoveItCpp & | operator= (const MoveItCpp &)=delete |
| MoveItCpp (MoveItCpp &&other)=default | |
| MoveItCpp & | operator= (MoveItCpp &&other)=default |
| ~MoveItCpp () | |
| Destructor. | |
| moveit::core::RobotModelConstPtr | getRobotModel () const |
| Get the RobotModel object. | |
| const rclcpp::Node::SharedPtr & | getNode () const |
| Get the ROS node this instance operates on. | |
| bool | getCurrentState (moveit::core::RobotStatePtr ¤t_state, double wait_seconds) |
| Get the current state queried from the current state monitor. | |
| moveit::core::RobotStatePtr | getCurrentState (double wait_seconds=0.0) |
| Get the current state queried from the current state monitor. | |
| const std::unordered_map< std::string, planning_pipeline::PlanningPipelinePtr > & | getPlanningPipelines () const |
| Get all loaded planning pipeline instances mapped to their reference names. | |
| planning_scene_monitor::PlanningSceneMonitorConstPtr | getPlanningSceneMonitor () const |
| Get the stored instance of the planning scene monitor. | |
| planning_scene_monitor::PlanningSceneMonitorPtr | getPlanningSceneMonitorNonConst () |
| std::shared_ptr< const tf2_ros::Buffer > | getTFBuffer () const |
| std::shared_ptr< tf2_ros::Buffer > | getTFBuffer () |
| trajectory_execution_manager::TrajectoryExecutionManagerConstPtr | getTrajectoryExecutionManager () const |
| Get the stored instance of the trajectory execution manager. | |
| trajectory_execution_manager::TrajectoryExecutionManagerPtr | getTrajectoryExecutionManagerNonConst () |
| moveit_controller_manager::ExecutionStatus | execute (const robot_trajectory::RobotTrajectoryPtr &robot_trajectory, bool blocking, const std::vector< std::string > &controllers=std::vector< std::string >()) |
| Execute a trajectory on the planning group specified by the robot's trajectory using the trajectory execution manager. | |
| moveit_controller_manager::ExecutionStatus | execute (const robot_trajectory::RobotTrajectoryPtr &robot_trajectory, const std::vector< std::string > &controllers=std::vector< std::string >()) |
| bool | terminatePlanningPipeline (const std::string &pipeline_name) |
| Utility to terminate the given planning pipeline. | |
Definition at line 54 of file moveit_cpp.hpp.
| moveit_cpp::MoveItCpp::MoveItCpp | ( | const rclcpp::Node::SharedPtr & | node | ) |
Constructor.
Definition at line 48 of file moveit_cpp.cpp.
| moveit_cpp::MoveItCpp::MoveItCpp | ( | const rclcpp::Node::SharedPtr & | node, |
| const Options & | options | ||
| ) |
|
delete |
This class owns unique resources (e.g. action clients, threads) and its not very meaningful to copy. Pass by references, move it, or simply create multiple instances where required.
|
default |
| moveit_cpp::MoveItCpp::~MoveItCpp | ( | ) |
Destructor.
Definition at line 85 of file moveit_cpp.cpp.
| moveit_controller_manager::ExecutionStatus moveit_cpp::MoveItCpp::execute | ( | const robot_trajectory::RobotTrajectoryPtr & | robot_trajectory, |
| bool | blocking, | ||
| const std::vector< std::string > & | controllers = std::vector<std::string>() |
||
| ) |
Execute a trajectory on the planning group specified by the robot's trajectory using the trajectory execution manager.
| [in] | robot_trajectory | Contains trajectory info as well as metadata such as a RobotModel. |
| [in] | controllers | An optional list of ros2_controllers to execute with. If none, MoveIt will attempt to find a controller. The exact behavior of finding a controller depends on which MoveItControllerManager plugin is active. |
Definition at line 197 of file moveit_cpp.cpp.


| moveit_controller_manager::ExecutionStatus moveit_cpp::MoveItCpp::execute | ( | const robot_trajectory::RobotTrajectoryPtr & | robot_trajectory, |
| const std::vector< std::string > & | controllers = std::vector<std::string>() |
||
| ) |
Definition at line 204 of file moveit_cpp.cpp.
| moveit::core::RobotStatePtr moveit_cpp::MoveItCpp::getCurrentState | ( | double | wait_seconds = 0.0 | ) |
Get the current state queried from the current state monitor.
| wait_seconds | the time in seconds for the state monitor to wait for a robot state. |
Definition at line 164 of file moveit_cpp.cpp.

| bool moveit_cpp::MoveItCpp::getCurrentState | ( | moveit::core::RobotStatePtr & | current_state, |
| double | wait_seconds | ||
| ) |
Get the current state queried from the current state monitor.
| wait_seconds | the time in seconds for the state monitor to wait for a robot state. |
Definition at line 150 of file moveit_cpp.cpp.

| const rclcpp::Node::SharedPtr & moveit_cpp::MoveItCpp::getNode | ( | ) | const |
Get the ROS node this instance operates on.
Definition at line 145 of file moveit_cpp.cpp.
| const std::unordered_map< std::string, planning_pipeline::PlanningPipelinePtr > & moveit_cpp::MoveItCpp::getPlanningPipelines | ( | ) | const |
Get all loaded planning pipeline instances mapped to their reference names.
Definition at line 171 of file moveit_cpp.cpp.
| planning_scene_monitor::PlanningSceneMonitorConstPtr moveit_cpp::MoveItCpp::getPlanningSceneMonitor | ( | ) | const |
Get the stored instance of the planning scene monitor.
Definition at line 176 of file moveit_cpp.cpp.
| planning_scene_monitor::PlanningSceneMonitorPtr moveit_cpp::MoveItCpp::getPlanningSceneMonitorNonConst | ( | ) |
Definition at line 181 of file moveit_cpp.cpp.
| moveit::core::RobotModelConstPtr moveit_cpp::MoveItCpp::getRobotModel | ( | ) | const |
Get the RobotModel object.
Definition at line 140 of file moveit_cpp.cpp.

| std::shared_ptr< tf2_ros::Buffer > moveit_cpp::MoveItCpp::getTFBuffer | ( | ) |
Definition at line 253 of file moveit_cpp.cpp.
| std::shared_ptr< const tf2_ros::Buffer > moveit_cpp::MoveItCpp::getTFBuffer | ( | ) | const |
Definition at line 249 of file moveit_cpp.cpp.
| trajectory_execution_manager::TrajectoryExecutionManagerConstPtr moveit_cpp::MoveItCpp::getTrajectoryExecutionManager | ( | ) | const |
Get the stored instance of the trajectory execution manager.
Definition at line 186 of file moveit_cpp.cpp.
| trajectory_execution_manager::TrajectoryExecutionManagerPtr moveit_cpp::MoveItCpp::getTrajectoryExecutionManagerNonConst | ( | ) |
Definition at line 191 of file moveit_cpp.cpp.
| bool moveit_cpp::MoveItCpp::terminatePlanningPipeline | ( | const std::string & | pipeline_name | ) |
Utility to terminate the given planning pipeline.
Definition at line 230 of file moveit_cpp.cpp.