Classes | Functions | Variables
moveit::planning_interface Namespace Reference

Simple interface to MoveIt! components. More...

Classes

class  MoveGroupInterface
 Client class to conveniently use the ROS interfaces provided by the move_group node. More...
 
class  MoveItErrorCode
 
class  PlanningSceneInterface
 

Functions

robot_model::RobotModelConstPtr getSharedRobotModel (const std::string &robot_description)
 
planning_scene_monitor::CurrentStateMonitorPtr getSharedStateMonitor (const robot_model::RobotModelConstPtr &robot_model, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer)
 getSharedStateMonitor is a simpler version of getSharedStateMonitor(const robot_model::RobotModelConstPtr &robot_model, const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, ros::NodeHandle nh = ros::NodeHandle() ). It calls this function using the default constructed ros::NodeHandle More...
 
planning_scene_monitor::CurrentStateMonitorPtr getSharedStateMonitor (const robot_model::RobotModelConstPtr &robot_model, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer, ros::NodeHandle nh)
 getSharedStateMonitor More...
 
std::shared_ptr< tf2_ros::BuffergetSharedTF ()
 
 MOVEIT_CLASS_FORWARD (PlanningSceneInterface)
 
 MOVEIT_CLASS_FORWARD (MoveGroupInterface)
 

Variables

const std::string GRASP_PLANNING_SERVICE_NAME = "plan_grasps"
 

Detailed Description

Simple interface to MoveIt! components.

Function Documentation

◆ getSharedRobotModel()

robot_model::RobotModelConstPtr moveit::planning_interface::getSharedRobotModel ( const std::string &  robot_description)

Definition at line 117 of file common_objects.cpp.

◆ getSharedStateMonitor() [1/2]

CurrentStateMonitorPtr moveit::planning_interface::getSharedStateMonitor ( const robot_model::RobotModelConstPtr &  robot_model,
const std::shared_ptr< tf2_ros::Buffer > &  tf_buffer 
)

getSharedStateMonitor is a simpler version of getSharedStateMonitor(const robot_model::RobotModelConstPtr &robot_model, const std::shared_ptr<tf2_ros::Buffer>& tf_buffer, ros::NodeHandle nh = ros::NodeHandle() ). It calls this function using the default constructed ros::NodeHandle

Parameters
robot_model
tf_buffer
Returns

Definition at line 135 of file common_objects.cpp.

◆ getSharedStateMonitor() [2/2]

CurrentStateMonitorPtr moveit::planning_interface::getSharedStateMonitor ( const robot_model::RobotModelConstPtr &  robot_model,
const std::shared_ptr< tf2_ros::Buffer > &  tf_buffer,
ros::NodeHandle  nh 
)

getSharedStateMonitor

Parameters
robot_model
tf_buffer
nhA ros::NodeHandle to pass node specific configurations, such as callbacks queues.
Returns

Definition at line 141 of file common_objects.cpp.

◆ getSharedTF()

std::shared_ptr< tf2_ros::Buffer > moveit::planning_interface::getSharedTF ( )

Definition at line 100 of file common_objects.cpp.

◆ MOVEIT_CLASS_FORWARD() [1/2]

moveit::planning_interface::MOVEIT_CLASS_FORWARD ( PlanningSceneInterface  )

◆ MOVEIT_CLASS_FORWARD() [2/2]

moveit::planning_interface::MOVEIT_CLASS_FORWARD ( MoveGroupInterface  )

Variable Documentation

◆ GRASP_PLANNING_SERVICE_NAME

const std::string moveit::planning_interface::GRASP_PLANNING_SERVICE_NAME = "plan_grasps"

Definition at line 78 of file move_group_interface.cpp.



planning_interface
Author(s): Ioan Sucan
autogenerated on Mon Dec 17 2018 03:53:04