Classes | Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes | 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

bool 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...
 
moveit::core::RobotStatePtr getCurrentState (double wait_seconds=0.0)
 Get the current state queried from the current state monitor. More...
 
bool getCurrentState (moveit::core::RobotStatePtr &current_state, double wait_seconds)
 Get the current state queried from the current state monitor. More...
 
const ros::NodeHandlegetNodeHandle () const
 Get the ROS node handle of this instance operates on. More...
 
const std::map< std::string, planning_pipeline::PlanningPipelinePtr > & getPlanningPipelines () const
 Get all loaded planning pipeline instances mapped to their reference names. More...
 
planning_scene_monitor::PlanningSceneMonitorConstPtr getPlanningSceneMonitor () const
 Get the stored instance of the planning scene monitor. More...
 
planning_scene_monitor::PlanningSceneMonitorPtr getPlanningSceneMonitorNonConst ()
 
moveit::core::RobotModelConstPtr getRobotModel () const
 Get the RobotModel object. More...
 
std::shared_ptr< tf2_ros::BuffergetTFBuffer ()
 
std::shared_ptr< const tf2_ros::BuffergetTFBuffer () const
 
trajectory_execution_manager::TrajectoryExecutionManagerConstPtr getTrajectoryExecutionManager () const
 Get the stored instance of the trajectory execution manager. More...
 
trajectory_execution_manager::TrajectoryExecutionManagerPtr getTrajectoryExecutionManagerNonConst ()
 
 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 (const Options &options, const ros::NodeHandle &nh, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer={})
 
 MoveItCpp (const ros::NodeHandle &nh, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer={})
 Constructor. More...
 
 MoveItCpp (MoveItCpp &&other)=default
 
MoveItCppoperator= (const MoveItCpp &)=delete
 
MoveItCppoperator= (MoveItCpp &&other)=default
 
bool terminatePlanningPipeline (std::string const &pipeline_name)
 Utility to terminate a given planning pipeline. More...
 
 ~MoveItCpp ()
 Destructor. More...
 

Protected Attributes

std::shared_ptr< tf2_ros::Buffertf_buffer_
 
std::shared_ptr< tf2_ros::TransformListenertf_listener_
 

Private Member Functions

bool loadPlanningPipelines (const PlanningPipelineOptions &options)
 Initialize and setup the planning pipelines. More...
 
bool loadPlanningSceneMonitor (const PlanningSceneMonitorOptions &options)
 Initialize and setup the planning scene monitor. More...
 

Private Attributes

std::map< std::string, std::set< std::string > > groups_algorithms_map_
 
ros::NodeHandle node_handle_
 
std::map< std::string, planning_pipeline::PlanningPipelinePtr > planning_pipelines_
 
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
 
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_
 

Detailed Description

Definition at line 86 of file moveit_cpp.h.

Constructor & Destructor Documentation

◆ MoveItCpp() [1/4]

moveit_cpp::MoveItCpp::MoveItCpp ( const ros::NodeHandle nh,
const std::shared_ptr< tf2_ros::Buffer > &  tf_buffer = {} 
)

Constructor.

Definition at line 77 of file moveit_cpp.cpp.

◆ MoveItCpp() [2/4]

moveit_cpp::MoveItCpp::MoveItCpp ( const Options options,
const ros::NodeHandle nh,
const std::shared_ptr< tf2_ros::Buffer > &  tf_buffer = {} 
)

Definition at line 82 of file moveit_cpp.cpp.

◆ MoveItCpp() [3/4]

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() [4/4]

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

◆ ~MoveItCpp()

moveit_cpp::MoveItCpp::~MoveItCpp ( )

Destructor.

Definition at line 121 of file moveit_cpp.cpp.

Member Function Documentation

◆ execute()

bool 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 258 of file moveit_cpp.cpp.

◆ 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 226 of file moveit_cpp.cpp.

◆ 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 211 of file moveit_cpp.cpp.

◆ getNodeHandle()

const ros::NodeHandle & moveit_cpp::MoveItCpp::getNodeHandle ( ) const

Get the ROS node handle of this instance operates on.

Definition at line 206 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 233 of file moveit_cpp.cpp.

◆ getPlanningSceneMonitor()

planning_scene_monitor::PlanningSceneMonitorConstPtr moveit_cpp::MoveItCpp::getPlanningSceneMonitor ( ) const

Get the stored instance of the planning scene monitor.

Definition at line 238 of file moveit_cpp.cpp.

◆ getPlanningSceneMonitorNonConst()

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

Definition at line 243 of file moveit_cpp.cpp.

◆ getRobotModel()

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

Get the RobotModel object.

Definition at line 201 of file moveit_cpp.cpp.

◆ getTFBuffer() [1/2]

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

◆ getTFBuffer() [2/2]

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

Definition at line 307 of file moveit_cpp.cpp.

◆ getTrajectoryExecutionManager()

trajectory_execution_manager::TrajectoryExecutionManagerConstPtr moveit_cpp::MoveItCpp::getTrajectoryExecutionManager ( ) const

Get the stored instance of the trajectory execution manager.

Definition at line 248 of file moveit_cpp.cpp.

◆ getTrajectoryExecutionManagerNonConst()

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

Definition at line 253 of file moveit_cpp.cpp.

◆ loadPlanningPipelines()

bool moveit_cpp::MoveItCpp::loadPlanningPipelines ( const PlanningPipelineOptions options)
private

Initialize and setup the planning pipelines.

Definition at line 162 of file moveit_cpp.cpp.

◆ loadPlanningSceneMonitor()

bool moveit_cpp::MoveItCpp::loadPlanningSceneMonitor ( const PlanningSceneMonitorOptions options)
private

Initialize and setup the planning scene monitor.

Definition at line 126 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

◆ terminatePlanningPipeline()

bool moveit_cpp::MoveItCpp::terminatePlanningPipeline ( std::string const &  pipeline_name)

Utility to terminate a given planning pipeline.

Definition at line 288 of file moveit_cpp.cpp.

Member Data Documentation

◆ groups_algorithms_map_

std::map<std::string, std::set<std::string> > moveit_cpp::MoveItCpp::groups_algorithms_map_
private

Definition at line 207 of file moveit_cpp.h.

◆ node_handle_

ros::NodeHandle moveit_cpp::MoveItCpp::node_handle_
private

Definition at line 202 of file moveit_cpp.h.

◆ planning_pipelines_

std::map<std::string, planning_pipeline::PlanningPipelinePtr> moveit_cpp::MoveItCpp::planning_pipelines_
private

Definition at line 206 of file moveit_cpp.h.

◆ planning_scene_monitor_

planning_scene_monitor::PlanningSceneMonitorPtr moveit_cpp::MoveItCpp::planning_scene_monitor_
private

Definition at line 203 of file moveit_cpp.h.

◆ tf_buffer_

std::shared_ptr<tf2_ros::Buffer> moveit_cpp::MoveItCpp::tf_buffer_
protected

Definition at line 197 of file moveit_cpp.h.

◆ tf_listener_

std::shared_ptr<tf2_ros::TransformListener> moveit_cpp::MoveItCpp::tf_listener_
protected

Definition at line 198 of file moveit_cpp.h.

◆ trajectory_execution_manager_

trajectory_execution_manager::TrajectoryExecutionManagerPtr moveit_cpp::MoveItCpp::trajectory_execution_manager_
private

Definition at line 210 of file moveit_cpp.h.


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


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Apr 18 2024 02:24:19