Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes
moveit_object_handling::GraspedObjectHandlerMoveIt Class Reference

#include <GraspedObjectHandler.h>

Inheritance diagram for moveit_object_handling::GraspedObjectHandlerMoveIt:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool attachObjectToRobot (const std::string &object_name, const std::string &attach_link_name)
virtual bool detachObjectFromRobot (const std::string &object_name)
 GraspedObjectHandlerMoveIt (ros::NodeHandle &n, const std::vector< std::string > &_gripperLinkNames, const std::string &get_planning_scene_service="/get_planning_scene", const std::string &set_planning_scene_topic="/planning_scene")
void waitForSubscribers ()

Private Member Functions

bool attachObjectToRobot (const std::string &name, const std::string &link_name, const std::vector< std::string > &allowedTouchLinks)
void subscribeAndAdvertise (const std::string &get_planning_scene_service="/get_planning_scene", const std::string &set_planning_scene_topic="/planning_scene")
bool transformCollisionObject (const std::string &to_frame, moveit_msgs::CollisionObject &collision_object)
bool transformPose (const geometry_msgs::Pose &pose, const std::string &from_frame, const std::string &to_frame, geometry_msgs::Pose &p)

Static Private Member Functions

static bool hasObject (const std::string &name, const std::vector< moveit_msgs::AttachedCollisionObject > &objs, moveit_msgs::AttachedCollisionObject &o)
static bool hasObject (const std::string &name, const std::vector< moveit_msgs::CollisionObject > &objs, moveit_msgs::CollisionObject &o)
static bool removeObject (const std::string &name, std::vector< moveit_msgs::CollisionObject > &objs)
static bool removeObject (const std::string &name, std::vector< moveit_msgs::AttachedCollisionObject > &objs)

Private Attributes

std::vector< std::string > gripperLinkNames
ros::ServiceClient moveit_planning_scene_client
ros::Publisher moveit_planning_scene_publisher
ros::NodeHandlenode

Detailed Description

Implementation of GraspedObjectHandler for MoveIt! collision object.

Author:
Jennifer Buehler
Date:
February 2016

Definition at line 46 of file GraspedObjectHandler.h.


Constructor & Destructor Documentation

GraspedObjectHandlerMoveIt::GraspedObjectHandlerMoveIt ( ros::NodeHandle n,
const std::vector< std::string > &  _gripperLinkNames,
const std::string &  get_planning_scene_service = "/get_planning_scene",
const std::string &  set_planning_scene_topic = "/planning_scene" 
)
Parameters:
_gripperLinkNamesnames of the gripper links. Those are the links which are allowed to collide with the object being grasped (moveit_msgs::AttachedCollisionObject.touch_links)

Definition at line 9 of file GraspedObjectHandler.cpp.


Member Function Documentation

bool GraspedObjectHandlerMoveIt::attachObjectToRobot ( const std::string &  object_name,
const std::string &  attach_link_name 
) [virtual]
bool GraspedObjectHandlerMoveIt::attachObjectToRobot ( const std::string &  name,
const std::string &  link_name,
const std::vector< std::string > &  allowedTouchLinks 
) [private]

Definition at line 92 of file GraspedObjectHandler.cpp.

bool GraspedObjectHandlerMoveIt::detachObjectFromRobot ( const std::string &  object_name) [virtual]
bool GraspedObjectHandlerMoveIt::hasObject ( const std::string &  name,
const std::vector< moveit_msgs::AttachedCollisionObject > &  objs,
moveit_msgs::AttachedCollisionObject &  o 
) [static, private]

Definition at line 186 of file GraspedObjectHandler.cpp.

bool GraspedObjectHandlerMoveIt::hasObject ( const std::string &  name,
const std::vector< moveit_msgs::CollisionObject > &  objs,
moveit_msgs::CollisionObject &  o 
) [static, private]

Definition at line 200 of file GraspedObjectHandler.cpp.

bool GraspedObjectHandlerMoveIt::removeObject ( const std::string &  name,
std::vector< moveit_msgs::CollisionObject > &  objs 
) [static, private]

Definition at line 214 of file GraspedObjectHandler.cpp.

bool GraspedObjectHandlerMoveIt::removeObject ( const std::string &  name,
std::vector< moveit_msgs::AttachedCollisionObject > &  objs 
) [static, private]

Definition at line 228 of file GraspedObjectHandler.cpp.

void GraspedObjectHandlerMoveIt::subscribeAndAdvertise ( const std::string &  get_planning_scene_service = "/get_planning_scene",
const std::string &  set_planning_scene_topic = "/planning_scene" 
) [private]

Definition at line 242 of file GraspedObjectHandler.cpp.

bool GraspedObjectHandlerMoveIt::transformCollisionObject ( const std::string &  to_frame,
moveit_msgs::CollisionObject &  collision_object 
) [private]

Transform all object poses to the given frame

Definition at line 290 of file GraspedObjectHandler.cpp.

bool GraspedObjectHandlerMoveIt::transformPose ( const geometry_msgs::Pose pose,
const std::string &  from_frame,
const std::string &  to_frame,
geometry_msgs::Pose p 
) [private]

Definition at line 259 of file GraspedObjectHandler.cpp.

Definition at line 249 of file GraspedObjectHandler.cpp.


Member Data Documentation

Definition at line 90 of file GraspedObjectHandler.h.

Definition at line 85 of file GraspedObjectHandler.h.

Definition at line 86 of file GraspedObjectHandler.h.

Definition at line 88 of file GraspedObjectHandler.h.


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


moveit_object_handling
Author(s): Jennifer Buehler
autogenerated on Sat Mar 2 2019 03:50:51