36 #define BOOST_PARAMETER_MAX_ARITY 7 57 "Color", QColor(25, 255, 0),
58 "Color to draw the polygons.",
62 "Amount of transparency to apply to the polygon.",
66 "only shows the borders of polygons",
70 "show normal direction",
73 "enable lighting",
true,
94 for (
size_t i = 0; i <
lines_.size(); i++) {
98 for (
size_t i = 0; i <
materials_.size(); i++) {
123 static uint32_t
count = 0;
126 for (
size_t i =
materials_.size(); num > i; i++) {
127 std::stringstream ss;
128 ss <<
"PolygonArrayMaterial" << count++;
129 Ogre::MaterialPtr material
130 = Ogre::MaterialManager::getSingleton().create(ss.str(),
"rviz");
131 material->setReceiveShadows(
false);
133 material->getTechnique(0)->setAmbient(0.5, 0.5, 0.5);
143 for (
size_t i = 0; i < msg.polygons.size(); i++) {
159 const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
161 int scale_factor = 2;
167 i < msg->polygons.size() * scale_factor;
169 Ogre::SceneNode* scene_node
171 Ogre::ManualObject* manual_object
173 manual_object->setDynamic(
true);
174 scene_node->attachObject(manual_object);
179 else if (msg->polygons.size() * scale_factor <
manual_objects_.size()) {
180 for (
size_t i = msg->polygons.size() * scale_factor;
187 for (
size_t i =
arrow_objects_.size(); i < msg->polygons.size(); i++) {
188 Ogre::SceneNode* scene_node =
scene_node_->createChildSceneNode();
190 scene_node->setVisible(
false);
196 for (
size_t i = msg->polygons.size(); i <
arrow_nodes_.size(); i++) {
205 if (num >
lines_.size()) {
206 for (
size_t i =
lines_.size(); i < num; i++) {
215 for (
size_t i = 0; i <
lines_.size(); i++) {
222 Ogre::ColourValue color;
225 color.r = ros_color.r;
226 color.g = ros_color.g;
227 color.b = ros_color.b;
228 color.a = ros_color.a;
238 "Message does not have lieklihood fields");
241 std_msgs::ColorRGBA ros_color
243 color.r = ros_color.r;
244 color.g = ros_color.g;
245 color.b = ros_color.b;
246 color.a = ros_color.a;
254 "Message does not have lebels fields");
257 std_msgs::ColorRGBA ros_color
259 color.r = ros_color.r;
260 color.g = ros_color.g;
261 color.b = ros_color.b;
262 color.a = ros_color.a;
271 const geometry_msgs::PolygonStamped& polygon)
275 Ogre::Vector3 position;
276 Ogre::Quaternion orientation;
277 if (!
getTransform(polygon.header, position, orientation))
279 scene_node->setPosition(position);
280 scene_node->setOrientation(orientation);
285 Ogre::ColourValue color =
getColor(i);
286 line->
setColor(color.r, color.g, color.b, color.a);
288 for (
size_t i = 0; i < polygon.polygon.points.size(); ++i) {
289 Ogre::Vector3 step_position;
290 step_position.x = polygon.polygon.points[i].x;
291 step_position.y = polygon.polygon.points[i].y;
292 step_position.z = polygon.polygon.points[i].z;
295 Ogre::Vector3 step_position;
296 step_position.x = polygon.polygon.points[0].x;
297 step_position.y = polygon.polygon.points[0].y;
298 step_position.z = polygon.polygon.points[0].z;
304 Ogre::ColourValue color =
getColor(i);
306 materials_[i]->getTechnique(0)->setAmbient(color * 0.5);
307 materials_[i]->getTechnique(0)->setDiffuse(color);
308 if (color.a < 0.9998) {
309 materials_[i]->getTechnique(0)->setSceneBlending(
310 Ogre::SBT_TRANSPARENT_ALPHA);
311 materials_[i]->getTechnique(0)->setDepthWriteEnabled(
false);
314 materials_[i]->getTechnique(0)->setSceneBlending(Ogre::SBT_REPLACE);
315 materials_[i]->getTechnique(0)->setDepthWriteEnabled(
true);
318 materials_[i]->getTechnique(0)->setAmbient(color * 0.5);
319 materials_[i]->getTechnique(0)->setDiffuse(color);
323 const size_t i,
const geometry_msgs::PolygonStamped& polygon)
325 Ogre::Vector3 position;
326 Ogre::Quaternion orientation;
327 if (!
getTransform(polygon.header, position, orientation))
333 Ogre::ColourValue color =
getColor(i);
334 scene_node->setPosition(position);
335 scene_node->setOrientation(orientation);
336 manual_object->clear();
337 manual_object->setVisible(
true);
341 std::vector<jsk_recognition_utils::Polygon::Ptr>
344 uint32_t num_points = 0;
345 for (
size_t j = 0; j < triangles.size(); j++) {
346 num_points += triangles[j]->getNumVertices();
349 manual_object->estimateVertexCount(num_points * 2);
350 manual_object->begin(
352 for (
size_t ii = 0; ii < triangles.size(); ii++) {
354 size_t num_vertices = triangle->getNumVertices();
355 for (
size_t j = 0; j < num_vertices; j++) {
356 Eigen::Vector3f v = triangle->getVertex(j);
357 manual_object->position(v[0], v[1], v[2]);
358 manual_object->colour(color.r, color.g, color.b, color.a);
360 for (
int j = num_vertices - 1; j >= 0; j--) {
361 Eigen::Vector3f v = triangle->getVertex(j);
362 manual_object->position(v[0], v[1], v[2]);
363 manual_object->colour(color.r, color.g, color.b, color.a);
366 manual_object->end();
372 const size_t i,
const geometry_msgs::PolygonStamped& polygon)
375 scene_node->setVisible(
true);
377 Ogre::Vector3 position;
378 Ogre::Quaternion orientation;
379 if (!
getTransform(polygon.header, position, orientation))
381 scene_node->setPosition(position);
382 scene_node->setOrientation(orientation);
387 Eigen::Vector3f centroid(0, 0, 0);
388 if (vertices.size() == 0) {
392 for (
size_t j = 0; j < vertices.size(); j++) {
393 centroid = vertices[j] + centroid;
395 centroid = centroid / vertices.size();
397 Ogre::Vector3
pos(centroid[0], centroid[1], centroid[2]);
398 Eigen::Vector3f normal = geo_polygon.
getNormal();
399 Ogre::Vector3 direction(normal[0], normal[1], normal[2]);
400 if (std::isnan(direction[0]) || std::isnan(direction[1]) || std::isnan(direction[2])) {
401 ROS_ERROR(
"failed to compute normal direction");
402 Ogre::Vector3 zeroscale(0, 0, 0);
403 arrow->setScale(zeroscale);
407 arrow->setPosition(pos);
408 arrow->setDirection(direction);
410 arrow->setScale(scale);
415 const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
420 "Message contained invalid floating point values" 437 for (
size_t i = 0; i < msg->polygons.size(); i++) {
438 geometry_msgs::PolygonStamped polygon = msg->polygons[i];
439 if (polygon.polygon.points.size() >= 3) {
445 for (
size_t i = 0; i < msg->polygons.size(); i++) {
449 for (
size_t i = 0; i < msg->polygons.size(); i++) {
450 geometry_msgs::PolygonStamped polygon = msg->polygons[i];
456 for (
size_t i = 0; i < msg->polygons.size(); i++) {
457 geometry_msgs::PolygonStamped polygon = msg->polygons[i];
458 if (polygon.polygon.points.size() >= 3) {
466 const std_msgs::Header &
header,
467 Ogre::Vector3 &position, Ogre::Quaternion &orientation)
470 header.frame_id, header.stamp,
471 position, orientation);
473 std::ostringstream oss;
474 oss <<
"Error transforming from frame '";
475 oss << header.frame_id <<
"' to frame '";
479 "Transform", QString::fromStdString(oss.str()));
virtual QColor getColor() const
rviz::EnumProperty * coloring_property_
virtual bool getTransform(const std_msgs::Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
std::vector< Ogre::SceneNode * > arrow_nodes_
rviz::ColorProperty * color_property_
virtual void processMessage(const jsk_recognition_msgs::PolygonArray::ConstPtr &msg)
void addPoint(const Ogre::Vector3 &point)
void updateEnableLighting()
virtual void onInitialize()
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
DisplayContext * context_
virtual void processLine(const size_t i, const geometry_msgs::PolygonStamped &polygon)
virtual Vertices getVertices()
virtual float getFloat() const
virtual void allocateMaterials(int num)
virtual void updateLines(int num)
std::string coloring_method_
static Polygon fromROSMsg(const geometry_msgs::Polygon &polygon)
Ogre::SceneNode * scene_node_
rviz::BoolProperty * only_border_property_
jsk_recognition_msgs::PolygonArray::ConstPtr latest_msg_
rviz::BoolProperty * enable_lighting_property_
virtual void setColor(float r, float g, float b, float a)
virtual void processPolygonMaterial(const size_t i)
Ogre::ColourValue qtToOgre(const QColor &c)
virtual bool getBool() const
virtual void processPolygon(const size_t i, const geometry_msgs::PolygonStamped &polygon)
virtual void processNormal(const size_t i, const geometry_msgs::PolygonStamped &polygon)
virtual void addOption(const QString &option, int value=0)
virtual void updateSceneNodes(const jsk_recognition_msgs::PolygonArray::ConstPtr &msg)
std::vector< Ogre::SceneNode * > scene_nodes_
rviz::FloatProperty * normal_length_property_
bool validateFloats(const sensor_msgs::CameraInfo &msg)
std::vector< ArrowPtr > arrow_objects_
virtual FrameManager * getFrameManager() const =0
virtual ~PolygonArrayDisplay()
bool validateFloats(const visualization_msgs::InteractiveMarker &msg)
void setNumLines(uint32_t num)
#define ROS_DEBUG_STREAM(args)
void setMaxPointsPerLine(uint32_t max)
Ogre::SceneManager * scene_manager_
void updateNormalLength()
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
virtual Ogre::SceneManager * getSceneManager() const =0
std::vector< rviz::BillboardLine * > lines_
rviz::FloatProperty * alpha_property_
std::vector< Ogre::MaterialPtr > materials_
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
rviz::BoolProperty * show_normal_property_
std::vector< Ogre::ManualObject * > manual_objects_
virtual Ogre::ColourValue getColor(size_t index)
virtual void onInitialize()
virtual int getOptionInt()
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
virtual QString getName() const
virtual std::vector< Polygon::Ptr > decomposeToTriangles()
virtual Eigen::Vector3f getNormal()
void setLineWidth(float width)