Classes | Functions | Variables
moveit::planning_interface Namespace Reference

Simple interface to MoveIt! components. More...

Classes

class  MoveGroup
 Client class for the MoveGroup action. This class includes many default settings to make things easy to use. 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
planning_scene_monitor::CurrentStateMonitorPtr getSharedStateMonitor (const robot_model::RobotModelConstPtr &kmodel, const boost::shared_ptr< tf::Transformer > &tf, ros::NodeHandle nh)
 getSharedStateMonitor
boost::shared_ptr
< tf::Transformer
getSharedTF ()
 MOVEIT_CLASS_FORWARD (PlanningSceneInterface)
 MOVEIT_CLASS_FORWARD (MoveGroup)

Variables

const std::string GRASP_PLANNING_SERVICE_NAME = "plan_grasps"

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.

Definition at line 80 of file common_objects.cpp.


Variable Documentation

Definition at line 79 of file move_group.cpp.



planning_interface
Author(s): Ioan Sucan
autogenerated on Mon Jul 24 2017 02:22:06