moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <moveit_cpp.h>
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, const std::shared_ptr< tf2_ros::Buffer > &) | |
Constructor. More... | |
MoveItCpp (const rclcpp::Node::SharedPtr &node) | |
MoveItCpp (const rclcpp::Node::SharedPtr &node, const Options &options, const std::shared_ptr< tf2_ros::Buffer > &) | |
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. More... | |
MoveItCpp & | operator= (const MoveItCpp &)=delete |
MoveItCpp (MoveItCpp &&other)=default | |
MoveItCpp & | operator= (MoveItCpp &&other)=default |
~MoveItCpp () | |
Destructor. More... | |
moveit::core::RobotModelConstPtr | getRobotModel () const |
Get the RobotModel object. More... | |
const rclcpp::Node::SharedPtr & | getNode () const |
Get the ROS node this instance operates on. More... | |
bool | getCurrentState (moveit::core::RobotStatePtr ¤t_state, double wait_seconds) |
Get the current state queried from the current state monitor. More... | |
moveit::core::RobotStatePtr | getCurrentState (double wait_seconds=0.0) |
Get the current state queried from the current state monitor. More... | |
const std::map< std::string, planning_pipeline::PlanningPipelinePtr > & | getPlanningPipelines () const |
Get all loaded planning pipeline instances mapped to their reference names. More... | |
std::set< std::string > | getPlanningPipelineNames (const std::string &group_name="") const |
Get the names of all loaded planning pipelines. Specify group_name to filter the results by planning group. More... | |
const planning_scene_monitor::PlanningSceneMonitorPtr & | getPlanningSceneMonitor () const |
Get the stored instance of the planning scene monitor. More... | |
planning_scene_monitor::PlanningSceneMonitorPtr | getPlanningSceneMonitorNonConst () |
const std::shared_ptr< tf2_ros::Buffer > & | getTFBuffer () const |
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & | getTrajectoryExecutionManager () const |
Get the stored instance of the trajectory execution manager. More... | |
trajectory_execution_manager::TrajectoryExecutionManagerPtr | getTrajectoryExecutionManagerNonConst () |
moveit_controller_manager::ExecutionStatus | execute (const std::string &group_name, const robot_trajectory::RobotTrajectoryPtr &robot_trajectory, bool blocking=true) |
Execute a trajectory on the planning group specified by group_name using the trajectory execution manager. If blocking is set to false, the execution is run in background and the function returns immediately. More... | |
Definition at line 54 of file moveit_cpp.h.
|
inline |
Constructor.
Definition at line 111 of file moveit_cpp.h.
moveit_cpp::MoveItCpp::MoveItCpp | ( | const rclcpp::Node::SharedPtr & | node | ) |
Definition at line 49 of file moveit_cpp.cpp.
|
inline |
Definition at line 117 of file moveit_cpp.h.
moveit_cpp::MoveItCpp::MoveItCpp | ( | const rclcpp::Node::SharedPtr & | node, |
const Options & | options | ||
) |
Definition at line 53 of file moveit_cpp.cpp.
|
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 86 of file moveit_cpp.cpp.
moveit_controller_manager::ExecutionStatus moveit_cpp::MoveItCpp::execute | ( | const std::string & | group_name, |
const robot_trajectory::RobotTrajectoryPtr & | robot_trajectory, | ||
bool | blocking = true |
||
) |
Execute a trajectory on the planning group specified by group_name using the trajectory execution manager. If blocking is set to false, the execution is run in background and the function returns immediately.
Definition at line 248 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 203 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 189 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 184 of file moveit_cpp.cpp.
std::set< std::string > moveit_cpp::MoveItCpp::getPlanningPipelineNames | ( | const std::string & | group_name = "" | ) | const |
Get the names of all loaded planning pipelines. Specify group_name to filter the results by planning group.
Definition at line 215 of file moveit_cpp.cpp.
const std::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 210 of file moveit_cpp.cpp.
const planning_scene_monitor::PlanningSceneMonitorPtr & moveit_cpp::MoveItCpp::getPlanningSceneMonitor | ( | ) | const |
Get the stored instance of the planning scene monitor.
Definition at line 227 of file moveit_cpp.cpp.
planning_scene_monitor::PlanningSceneMonitorPtr moveit_cpp::MoveItCpp::getPlanningSceneMonitorNonConst | ( | ) |
Definition at line 232 of file moveit_cpp.cpp.
moveit::core::RobotModelConstPtr moveit_cpp::MoveItCpp::getRobotModel | ( | ) | const |
Get the RobotModel object.
Definition at line 179 of file moveit_cpp.cpp.
const std::shared_ptr< tf2_ros::Buffer > & moveit_cpp::MoveItCpp::getTFBuffer | ( | ) | const |
Definition at line 277 of file moveit_cpp.cpp.
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & moveit_cpp::MoveItCpp::getTrajectoryExecutionManager | ( | ) | const |
Get the stored instance of the trajectory execution manager.
Definition at line 237 of file moveit_cpp.cpp.
trajectory_execution_manager::TrajectoryExecutionManagerPtr moveit_cpp::MoveItCpp::getTrajectoryExecutionManagerNonConst | ( | ) |
Definition at line 242 of file moveit_cpp.cpp.