Classes | Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
moveit::planning_interface::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...
 
std::set< std::stringgetPlanningPipelineNames (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 std::map< std::string, planning_pipeline::PlanningPipelinePtr > & getPlanningPipelines () const
 Get all loaded planning pipeline instances mapped to their reference names. More...
 
const planning_scene_monitor::PlanningSceneMonitorPtr & 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...
 
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 ()
 
 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
 
 ~MoveItCpp ()
 Destructor. More...
 

Protected Attributes

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

Private Member Functions

void clearContents ()
 Reset all member variables. More...
 
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_
 
std::map< std::string, std::set< std::string > > groups_pipelines_map_
 
ros::NodeHandle node_handle_
 
std::map< std::string, planning_pipeline::PlanningPipelinePtr > planning_pipelines_
 
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
 
moveit::core::RobotModelConstPtr robot_model_
 
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_
 

Detailed Description

Definition at line 119 of file moveit_cpp.h.

Constructor & Destructor Documentation

◆ MoveItCpp() [1/4]

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

Constructor.

Definition at line 118 of file moveit_cpp.cpp.

◆ MoveItCpp() [2/4]

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

Definition at line 123 of file moveit_cpp.cpp.

◆ MoveItCpp() [3/4]

moveit::planning_interface::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::planning_interface::MoveItCpp::MoveItCpp ( MoveItCpp &&  other)
default

◆ ~MoveItCpp()

moveit::planning_interface::MoveItCpp::~MoveItCpp ( )

Destructor.

Definition at line 163 of file moveit_cpp.cpp.

Member Function Documentation

◆ clearContents()

void moveit::planning_interface::MoveItCpp::clearContents ( )
private

Reset all member variables.

Definition at line 371 of file moveit_cpp.cpp.

◆ execute()

bool moveit::planning_interface::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 337 of file moveit_cpp.cpp.

◆ getCurrentState() [1/2]

moveit::core::RobotStatePtr moveit::planning_interface::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 275 of file moveit_cpp.cpp.

◆ getCurrentState() [2/2]

bool moveit::planning_interface::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 260 of file moveit_cpp.cpp.

◆ getNodeHandle()

const ros::NodeHandle & moveit::planning_interface::MoveItCpp::getNodeHandle ( ) const

Get the ROS node handle of this instance operates on.

Definition at line 255 of file moveit_cpp.cpp.

◆ getPlanningPipelineNames()

std::set< std::string > moveit::planning_interface::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 287 of file moveit_cpp.cpp.

◆ getPlanningPipelines()

const std::map< std::string, planning_pipeline::PlanningPipelinePtr > & moveit::planning_interface::MoveItCpp::getPlanningPipelines ( ) const

Get all loaded planning pipeline instances mapped to their reference names.

Definition at line 282 of file moveit_cpp.cpp.

◆ getPlanningSceneMonitor()

const planning_scene_monitor::PlanningSceneMonitorPtr & moveit::planning_interface::MoveItCpp::getPlanningSceneMonitor ( ) const

Get the stored instance of the planning scene monitor.

Definition at line 317 of file moveit_cpp.cpp.

◆ getPlanningSceneMonitorNonConst()

planning_scene_monitor::PlanningSceneMonitorPtr moveit::planning_interface::MoveItCpp::getPlanningSceneMonitorNonConst ( )

Definition at line 322 of file moveit_cpp.cpp.

◆ getRobotModel()

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

Get the RobotModel object.

Definition at line 250 of file moveit_cpp.cpp.

◆ getTFBuffer()

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

Definition at line 366 of file moveit_cpp.cpp.

◆ getTrajectoryExecutionManager()

const trajectory_execution_manager::TrajectoryExecutionManagerPtr & moveit::planning_interface::MoveItCpp::getTrajectoryExecutionManager ( ) const

Get the stored instance of the trajectory execution manager.

Definition at line 327 of file moveit_cpp.cpp.

◆ getTrajectoryExecutionManagerNonConst()

trajectory_execution_manager::TrajectoryExecutionManagerPtr moveit::planning_interface::MoveItCpp::getTrajectoryExecutionManagerNonConst ( )

Definition at line 332 of file moveit_cpp.cpp.

◆ loadPlanningPipelines()

bool moveit::planning_interface::MoveItCpp::loadPlanningPipelines ( const PlanningPipelineOptions options)
private

Initialize and setup the planning pipelines.

Definition at line 200 of file moveit_cpp.cpp.

◆ loadPlanningSceneMonitor()

bool moveit::planning_interface::MoveItCpp::loadPlanningSceneMonitor ( const PlanningSceneMonitorOptions options)
private

Initialize and setup the planning scene monitor.

Definition at line 169 of file moveit_cpp.cpp.

◆ operator=() [1/2]

MoveItCpp& moveit::planning_interface::MoveItCpp::operator= ( const MoveItCpp )
delete

◆ operator=() [2/2]

MoveItCpp& moveit::planning_interface::MoveItCpp::operator= ( MoveItCpp &&  other)
default

Member Data Documentation

◆ groups_algorithms_map_

std::map<std::string, std::set<std::string> > moveit::planning_interface::MoveItCpp::groups_algorithms_map_
private

Definition at line 242 of file moveit_cpp.h.

◆ groups_pipelines_map_

std::map<std::string, std::set<std::string> > moveit::planning_interface::MoveItCpp::groups_pipelines_map_
private

Definition at line 241 of file moveit_cpp.h.

◆ node_handle_

ros::NodeHandle moveit::planning_interface::MoveItCpp::node_handle_
private

Definition at line 235 of file moveit_cpp.h.

◆ planning_pipelines_

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

Definition at line 240 of file moveit_cpp.h.

◆ planning_scene_monitor_

planning_scene_monitor::PlanningSceneMonitorPtr moveit::planning_interface::MoveItCpp::planning_scene_monitor_
private

Definition at line 237 of file moveit_cpp.h.

◆ robot_model_

moveit::core::RobotModelConstPtr moveit::planning_interface::MoveItCpp::robot_model_
private

Definition at line 236 of file moveit_cpp.h.

◆ tf_buffer_

std::shared_ptr<tf2_ros::Buffer> moveit::planning_interface::MoveItCpp::tf_buffer_
protected

Definition at line 230 of file moveit_cpp.h.

◆ tf_listener_

std::shared_ptr<tf2_ros::TransformListener> moveit::planning_interface::MoveItCpp::tf_listener_
protected

Definition at line 231 of file moveit_cpp.h.

◆ trajectory_execution_manager_

trajectory_execution_manager::TrajectoryExecutionManagerPtr moveit::planning_interface::MoveItCpp::trajectory_execution_manager_
private

Definition at line 245 of file moveit_cpp.h.


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


planning_interface
Author(s): Ioan Sucan
autogenerated on Tue Nov 24 2020 03:30:09