/collision_map_out (via mapping_rviz_plugin) not displaying in octomap_server
I am trying to display /collision_map_out topic. In RViz, I do have mapping_rviz_plugin installed and working. I have taken a look at the source code, as well as updated init.cpp
to contain PLUGINLIB_EXPORT_CLASS
instead of PLUGINLIB_DEPEND_CLASS
.
However, when I add the Display CollisionMap to RViz, I get the following error msg:
Object::connect: No such slot rviz::Display::changedOverrideColor()
Object::connect: (sender name: 'Override Color')
Object::connect: No such slot rviz::Display::changedColor()
Object::connect: (sender name: 'Color')
Object::connect: No such slot rviz::Display::changedRenderOperation()
Object::connect: (sender name: 'Render Operation')
Object::connect: No such slot rviz::Display::changedAlpha()
Object::connect: (sender name: 'Alpha')
Object::connect: No such slot rviz::Display::changedPointSize()
Object::connect: (sender name: 'Point Size')
Object::connect: No such slot rviz::Display::changedTopic()
Object::connect: (sender name: 'Topic')
The plugin cannot display the topic if the above methods are not working. How do I fix this?
The methods are from the source code, collision_map_display.cpp and collision_map_display.h
(here for completeness' sake):
#ifndef RVIZ_COLLISION_MAP_DISPLAY_H_
#define RVIZ_COLLISION_MAP_DISPLAY_H_
#include <rviz/display.h>
#include <rviz/helpers/color.h>
#include <boost/thread/mutex.hpp>
#include <boost/shared_ptr.hpp>
#include <arm_navigation_msgs/OrientedBoundingBox.h>
#include <arm_navigation_msgs/CollisionMap.h>
#include <message_filters/subscriber.h>
#include <tf/message_filter.h>
namespace rviz
{
class PointCloud;
class ColorProperty;
class RosTopicProperty;
class BoolProperty;
class EnumProperty;
class FloatProperty;
}
namespace Ogre
{
class SceneNode;
class ManualObject;
}
namespace mapping_rviz_plugin
{
namespace collision_render_ops
{
enum CollisionRenderOp
{
CBoxes, CPoints, CCount,
};
}
typedef collision_render_ops::CollisionRenderOp CollisionRenderOp;
/**
* \class CollisionMapDisplay
* \brief Displays a collision_map::CollisionMap message
*/
class CollisionMapDisplay : public rviz::Display
{
//Q_OBJECT
public:
CollisionMapDisplay();
virtual ~CollisionMapDisplay();
virtual void onInitialize();
void changedTopic();
void changedColor();
void changedOverrideColor();
void changedRenderOperation();
void changedPointSize();
void changedAlpha();
virtual void update(float wall_dt, float ros_dt);
virtual void reset();
protected:
void subscribe();
void unsubscribe();
void clear();
void incomingMessage(const arm_navigation_msgs::CollisionMap::ConstPtr& message);
void processMessage(const arm_navigation_msgs::CollisionMap::ConstPtr& message);
// overrides from Display
virtual void onEnable();
virtual void onDisable();
virtual void fixedFrameChanged();
std::string topic_;
rviz::Color color_;
int render_operation_;
bool override_color_;
float point_size_;
float alpha_;
Ogre::SceneNode* scene_node_;
rviz::PointCloud* cloud_;
arm_navigation_msgs::CollisionMap::ConstPtr current_message_;
message_filters::Subscriber<arm_navigation_msgs::CollisionMap> sub_;
tf::MessageFilter<arm_navigation_msgs::CollisionMap>* tf_filter_;
rviz::ColorProperty* color_property_;
rviz::RosTopicProperty* topic_property_;
rviz::BoolProperty* override_color_property_;
rviz::EnumProperty* render_operation_property_;
rviz::FloatProperty* point_size_property_;
rviz::FloatProperty* alpha_property_;
};
} // namespace mapping_rviz_plugin
/* RVIZ_COLLISION_MAP_DISPLAY_H_ */
#endif
Solved. Added Q_OBJECT and Q_SLOTS arguments. Also added fixed_frame_ argument to MessageFilter in collision_map_display.cpp. Works fine now.