#include <ObjectMessageGenerator.h>
Takes objects of type object_msgs/Object published a topic and transforms and re-publishes it into a moveit_msgs/CollisionObject.
The object information is read from incoming object_msgs/Object messages. If not all information is available, a service of type object_msgs/ObjectInfoRequest.srv is sent, e.g. to get the geometry details when required.
There are currently two ways to send object information to MoveIt!:
1. Publishing the collision object on /collision_objects which is read by move_group. 2. Another approach is described in [this PR2 tutorial](http://docs.ros.org/api/pr2_moveit_tutorials/html/planning/src/doc/planning_scene_ros_api_tutorial.html), in section *"Add object to environment": publising a planning scene diff (message moveit_msgs::PlanningScene)*.
The approach to be taken can be set with a ROS parameter is set for it.
The parameters for this class can be specified in a YAML file, which needs to be loaded onto the ROS parameter server under **namespace moveit_object_handling**. An example is given in the directory *config*, filename "CollisionObjectsGenerator.yaml"
Definition at line 45 of file ObjectMessageGenerator.h.
typedef object_msgs::ObjectInfo moveit_object_handling::ObjectMessageGenerator::ObjectInfoMsg [private] |
Definition at line 50 of file ObjectMessageGenerator.h.
typedef object_msgs::Object moveit_object_handling::ObjectMessageGenerator::ObjectMsg [private] |
Definition at line 49 of file ObjectMessageGenerator.h.
typedef std::map<std::string, moveit_msgs::CollisionObject> moveit_object_handling::ObjectMessageGenerator::ObjToPublishMap [private] |
Definition at line 51 of file ObjectMessageGenerator.h.
ObjectMessageGenerator::ObjectMessageGenerator | ( | ros::NodeHandle & | _node_priv, |
ros::NodeHandle & | _node | ||
) |
Definition at line 16 of file ObjectMessageGenerator.cpp.
ObjectMessageGenerator::~ObjectMessageGenerator | ( | ) | [virtual] |
Definition at line 90 of file ObjectMessageGenerator.cpp.
void ObjectMessageGenerator::connectPub | ( | const ros::SingleSubscriberPublisher & | p | ) | [private] |
Definition at line 94 of file ObjectMessageGenerator.cpp.
void ObjectMessageGenerator::disconnectPub | ( | const ros::SingleSubscriberPublisher & | p | ) | [private] |
Definition at line 122 of file ObjectMessageGenerator.cpp.
moveit_msgs::CollisionObject ObjectMessageGenerator::getCollisionGeometry | ( | const std::string & | name | ) | [private] |
Definition at line 288 of file ObjectMessageGenerator.cpp.
std::set< std::string > ObjectMessageGenerator::getCurrentAttachedCollisionObjectNames | ( | ) | [private] |
Definition at line 415 of file ObjectMessageGenerator.cpp.
std::vector< moveit_msgs::AttachedCollisionObject > ObjectMessageGenerator::getCurrentAttachedCollisionObjects | ( | ) | [private] |
Definition at line 391 of file ObjectMessageGenerator.cpp.
std::set< std::string > ObjectMessageGenerator::getCurrentCollisionObjectNames | ( | ) | [private] |
Definition at line 380 of file ObjectMessageGenerator.cpp.
std::vector< moveit_msgs::CollisionObject > ObjectMessageGenerator::getCurrentCollisionObjects | ( | bool | only_names = true | ) | [private] |
Definition at line 351 of file ObjectMessageGenerator.cpp.
bool ObjectMessageGenerator::isConnected | ( | ) | const |
Definition at line 112 of file ObjectMessageGenerator.cpp.
void ObjectMessageGenerator::publishCollisionsEvent | ( | const ros::TimerEvent & | e | ) | [private] |
Definition at line 132 of file ObjectMessageGenerator.cpp.
void ObjectMessageGenerator::receiveObject | ( | const ObjectMsg & | msg | ) | [private] |
Callback for object message
Definition at line 158 of file ObjectMessageGenerator.cpp.
moveit_msgs::CollisionObject ObjectMessageGenerator::transferContent | ( | const ObjectMsg & | msg, |
bool | skipGeometry | ||
) | [private] |
Helper to transfer contents from ObjectMsg to moveit_msgs::CollisionObject
Definition at line 317 of file ObjectMessageGenerator.cpp.
void ObjectMessageGenerator::updatePose | ( | const ObjectMsg & | newObj, |
moveit_msgs::CollisionObject & | obj | ||
) | [private] |
updates pose data in obj with information in newObj, leaves all other fields untouched
Definition at line 306 of file ObjectMessageGenerator.cpp.
Definition at line 126 of file ObjectMessageGenerator.h.
std::set<std::string> moveit_object_handling::ObjectMessageGenerator::addedObjects [private] |
Definition at line 112 of file ObjectMessageGenerator.h.
std::vector<std::string> moveit_object_handling::ObjectMessageGenerator::allowedCollisionLinks [private] |
Definition at line 124 of file ObjectMessageGenerator.h.
std::string moveit_object_handling::ObjectMessageGenerator::COLLISION_OBJECT_TOPIC [private] |
Definition at line 95 of file ObjectMessageGenerator.h.
Definition at line 101 of file ObjectMessageGenerator.h.
std::string moveit_object_handling::ObjectMessageGenerator::GET_PLANNING_SCENE_SERVICE [private] |
Definition at line 96 of file ObjectMessageGenerator.h.
Definition at line 135 of file ObjectMessageGenerator.h.
boost::mutex moveit_object_handling::ObjectMessageGenerator::mutex [private] |
Definition at line 130 of file ObjectMessageGenerator.h.
Definition at line 92 of file ObjectMessageGenerator.h.
Definition at line 92 of file ObjectMessageGenerator.h.
Definition at line 106 of file ObjectMessageGenerator.h.
Definition at line 104 of file ObjectMessageGenerator.h.
std::string moveit_object_handling::ObjectMessageGenerator::OBJECTS_TOPIC [private] |
Definition at line 93 of file ObjectMessageGenerator.h.
Definition at line 128 of file ObjectMessageGenerator.h.
Definition at line 108 of file ObjectMessageGenerator.h.
Definition at line 102 of file ObjectMessageGenerator.h.
Definition at line 98 of file ObjectMessageGenerator.h.
Definition at line 132 of file ObjectMessageGenerator.h.
std::string moveit_object_handling::ObjectMessageGenerator::REQUEST_OBJECTS_TOPIC [private] |
Definition at line 94 of file ObjectMessageGenerator.h.
std::string moveit_object_handling::ObjectMessageGenerator::SET_PLANNING_SCENE_TOPIC [private] |
Definition at line 97 of file ObjectMessageGenerator.h.
std::set<std::string> moveit_object_handling::ObjectMessageGenerator::skipObjects [private] |
Definition at line 117 of file ObjectMessageGenerator.h.
Definition at line 99 of file ObjectMessageGenerator.h.