moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Member Functions | List of all members
moveit_cpp::MoveItCpp Class Reference

#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...
 
MoveItCppoperator= (const MoveItCpp &)=delete
 
 MoveItCpp (MoveItCpp &&other)=default
 
MoveItCppoperator= (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 &current_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...
 

Detailed Description

Definition at line 54 of file moveit_cpp.h.

Constructor & Destructor Documentation

◆ MoveItCpp() [1/6]

moveit_cpp::MoveItCpp::MoveItCpp ( const rclcpp::Node::SharedPtr &  node,
const std::shared_ptr< tf2_ros::Buffer > &   
)
inline

Constructor.

Definition at line 111 of file moveit_cpp.h.

◆ MoveItCpp() [2/6]

moveit_cpp::MoveItCpp::MoveItCpp ( const rclcpp::Node::SharedPtr &  node)

Definition at line 49 of file moveit_cpp.cpp.

◆ MoveItCpp() [3/6]

moveit_cpp::MoveItCpp::MoveItCpp ( const rclcpp::Node::SharedPtr &  node,
const Options options,
const std::shared_ptr< tf2_ros::Buffer > &   
)
inline

Definition at line 117 of file moveit_cpp.h.

◆ MoveItCpp() [4/6]

moveit_cpp::MoveItCpp::MoveItCpp ( const rclcpp::Node::SharedPtr &  node,
const Options options 
)

Definition at line 53 of file moveit_cpp.cpp.

◆ MoveItCpp() [5/6]

moveit_cpp::MoveItCpp::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() [6/6]

moveit_cpp::MoveItCpp::MoveItCpp ( MoveItCpp &&  other)
default

◆ ~MoveItCpp()

moveit_cpp::MoveItCpp::~MoveItCpp ( )

Destructor.

Definition at line 86 of file moveit_cpp.cpp.

Member Function Documentation

◆ execute()

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.

Here is the caller graph for this function:

◆ getCurrentState() [1/2]

moveit::core::RobotStatePtr moveit_cpp::MoveItCpp::getCurrentState ( double  wait_seconds = 0.0)

Get the current state queried from the current state monitor.

Parameters
wait_secondsthe time in seconds for the state monitor to wait for a robot state.

Definition at line 203 of file moveit_cpp.cpp.

Here is the call graph for this function:

◆ getCurrentState() [2/2]

bool moveit_cpp::MoveItCpp::getCurrentState ( moveit::core::RobotStatePtr &  current_state,
double  wait_seconds 
)

Get the current state queried from the current state monitor.

Parameters
wait_secondsthe time in seconds for the state monitor to wait for a robot state.

Definition at line 189 of file moveit_cpp.cpp.

Here is the caller graph for this function:

◆ getNode()

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.

◆ getPlanningPipelineNames()

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.

◆ getPlanningPipelines()

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.

◆ getPlanningSceneMonitor()

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.

◆ getPlanningSceneMonitorNonConst()

planning_scene_monitor::PlanningSceneMonitorPtr moveit_cpp::MoveItCpp::getPlanningSceneMonitorNonConst ( )

Definition at line 232 of file moveit_cpp.cpp.

◆ getRobotModel()

moveit::core::RobotModelConstPtr moveit_cpp::MoveItCpp::getRobotModel ( ) const

Get the RobotModel object.

Definition at line 179 of file moveit_cpp.cpp.

◆ getTFBuffer()

const std::shared_ptr< tf2_ros::Buffer > & moveit_cpp::MoveItCpp::getTFBuffer ( ) const

Definition at line 277 of file moveit_cpp.cpp.

◆ getTrajectoryExecutionManager()

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.

◆ getTrajectoryExecutionManagerNonConst()

trajectory_execution_manager::TrajectoryExecutionManagerPtr moveit_cpp::MoveItCpp::getTrajectoryExecutionManagerNonConst ( )

Definition at line 242 of file moveit_cpp.cpp.

◆ operator=() [1/2]

MoveItCpp& moveit_cpp::MoveItCpp::operator= ( const MoveItCpp )
delete

◆ operator=() [2/2]

MoveItCpp& moveit_cpp::MoveItCpp::operator= ( MoveItCpp &&  other)
default

The documentation for this class was generated from the following files: