Classes | Functions | Variables
moveit::planning_interface Namespace Reference

Simple interface to MoveIt! components. More...

Classes

class  MoveGroup
 Deprecated Client interface to access interfaces of the move_group node. More...
 
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 &kmodel, const boost::shared_ptr< tf::Transformer > &tf)
 getSharedStateMonitor is a simpler version of getSharedStateMonitor(const robot_model::RobotModelConstPtr &kmodel, const boost::shared_ptr<tf::Transformer> &tf, 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 &kmodel, const boost::shared_ptr< tf::Transformer > &tf, ros::NodeHandle nh)
 getSharedStateMonitor More...
 
boost::shared_ptr< tf::TransformergetSharedTF ()
 
 MOVEIT_CLASS_FORWARD (PlanningSceneInterface)
 
 MOVEIT_CLASS_FORWARD (MoveGroupInterface)
 

Variables

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

Detailed Description

Simple interface to MoveIt! components.

Function Documentation

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

Definition at line 89 of file common_objects.cpp.

planning_scene_monitor::CurrentStateMonitorPtr moveit::planning_interface::getSharedStateMonitor ( const robot_model::RobotModelConstPtr &  kmodel,
const boost::shared_ptr< tf::Transformer > &  tf 
)

getSharedStateMonitor is a simpler version of getSharedStateMonitor(const robot_model::RobotModelConstPtr &kmodel, const boost::shared_ptr<tf::Transformer> &tf, ros::NodeHandle nh = ros::NodeHandle() ). It calls this function using the default constructed ros::NodeHandle

Parameters
kmodel
tf
Returns

Definition at line 105 of file common_objects.cpp.

planning_scene_monitor::CurrentStateMonitorPtr moveit::planning_interface::getSharedStateMonitor ( const robot_model::RobotModelConstPtr &  kmodel,
const boost::shared_ptr< tf::Transformer > &  tf,
ros::NodeHandle  nh 
)

getSharedStateMonitor

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

Definition at line 111 of file common_objects.cpp.

boost::shared_ptr< tf::Transformer > moveit::planning_interface::getSharedTF ( )

Definition at line 80 of file common_objects.cpp.

moveit::planning_interface::MOVEIT_CLASS_FORWARD ( PlanningSceneInterface  )
moveit::planning_interface::MOVEIT_CLASS_FORWARD ( MoveGroupInterface  )

Variable Documentation

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

Definition at line 78 of file move_group_interface.cpp.

moveit::planning_interface::MoveGroup moveit::planning_interface::MOVEIT_DEPRECATED


planning_interface
Author(s): Ioan Sucan
autogenerated on Wed Jul 10 2019 04:04:11