Skip to content
Snippets Groups Projects
Commit 8d294882 authored by Jennifer Buehler's avatar Jennifer Buehler
Browse files

fixed so it now compiles in Docker

parent 3aa7689c
No related branches found
No related tags found
No related merge requests found
FROM jenniferbuehler/TODO:general-message-pkgs
FROM jenniferbuehler/general-message-pkgs
MAINTAINER Jennifer Buehler
......
......@@ -13,28 +13,21 @@
#include <gazebo_test_tools/RecognizeGazeboObjectResponse.h>
#include <geometry_msgs/Pose.h>
#include <moveit_msgs/CollisionObject.h>
#include <moveit_msgs/GetPlanningScene.h>
#include <moveit_msgs/PlanningScene.h>
#include <boost/thread/mutex.hpp>
namespace gazebo_test_tools
{
/**
* This is a helper for *moveit_object/CollisionObjectGenerator*: A object_msgs/Object is
* *only* published after a service request of type *gazebo_test_tools/RecognizeGazeboObject*
* is sent to this helper. This avoids *object_msgs/Object*
* messages *continuosuly* having to be published and instead allows more control about when new
* object information is available, as it would be with a regular object recognition.
* Provides a service which publishes a object_msgs/Object,
* after the a service request of type *gazebo_test_tools/RecognizeGazeboObject* is received.
*
* Note that the class gazebo_state_plugins/GazeboObjectInfo also offers the functionality
* to continusously publish object_msgs/Object.msg, but it does so for *all* existing
* objects (except the ones excluded at start-up).
* With the FakeObjectRecognizer, it is possible to switch on/off the publishing
* of object_msgs/Object information for specific objects only at various times.
* Because of this, when you use FakeObjectRecogniser to send information to
* moveit_object/CollisionObjectGenerator, you will need to make sure that
* Because of this, when you use FakeObjectRecogniser, you will need to make sure that
* gazebo_state_plugins/GazeboObjectInfo is run with this parameter set to false:
*
* ``gazebo_state_plugins/publish_world_objects: false``
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment