grid_cells_display.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <boost/bind/bind.hpp>
31 #include <OgreSceneNode.h>
32 #include <OgreSceneManager.h>
33 #include <OgreManualObject.h>
34 
35 #include <rviz/frame_manager.h>
41 #include <rviz/validate_floats.h>
42 #include <rviz/display_context.h>
43 
44 #include "grid_cells_display.h"
45 
46 namespace rviz
47 {
48 GridCellsDisplay::GridCellsDisplay() : MFDClass(), last_frame_count_(uint64_t(-1))
49 {
50  color_property_ = new ColorProperty("Color", QColor(25, 255, 0), "Color of the grid cells.", this);
51 
52  alpha_property_ = new FloatProperty("Alpha", 1.0, "Amount of transparency to apply to the cells.",
56 }
57 
59 {
60  static int count = 0;
61  std::stringstream ss;
62  ss << "PolyLine" << count++;
63 
64  cloud_ = new PointCloud();
66  cloud_->setCommonDirection(Ogre::Vector3::UNIT_Z);
67  cloud_->setCommonUpVector(Ogre::Vector3::UNIT_Y);
68  scene_node_->attachObject(cloud_);
69  updateAlpha();
70 
72 }
73 
75 {
76  if (initialized())
77  {
78  unsubscribe();
80  scene_node_->detachObject(cloud_);
81  delete cloud_;
82  }
83 }
84 
86 {
88  cloud_->clear();
89 }
90 
92 {
95 }
96 
97 bool validateFloats(const nav_msgs::GridCells& msg)
98 {
99  bool valid = true;
100  valid = valid && validateFloats(msg.cell_width);
101  valid = valid && validateFloats(msg.cell_height);
102  valid = valid && validateFloats(msg.cells);
103  return valid;
104 }
105 
106 void GridCellsDisplay::processMessage(const nav_msgs::GridCells::ConstPtr& msg)
107 {
109  return;
111 
112  cloud_->clear();
113 
114  if (!validateFloats(*msg))
115  {
117  "Message contained invalid floating point values (nans or infs)");
118  return;
119  }
120 
121  Ogre::Vector3 position;
122  Ogre::Quaternion orientation;
123  if (!context_->getFrameManager()->getTransform(msg->header, position, orientation))
124  {
125  ROS_DEBUG("Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(),
126  qPrintable(fixed_frame_));
127  }
128 
129  scene_node_->setPosition(position);
130  scene_node_->setOrientation(orientation);
131 
132  if (msg->cell_width == 0)
133  {
134  setStatus(StatusProperty::Error, "Topic", "Cell width is zero, cells will be invisible.");
135  }
136  else if (msg->cell_height == 0)
137  {
138  setStatus(StatusProperty::Error, "Topic", "Cell height is zero, cells will be invisible.");
139  }
140 
141  cloud_->setDimensions(msg->cell_width, msg->cell_height, 0.0);
142 
143  Ogre::ColourValue color_int = qtToOgre(color_property_->getColor());
144  uint32_t num_points = msg->cells.size();
145 
146  typedef std::vector<PointCloud::Point> V_Point;
147  V_Point points;
148  points.resize(num_points);
149  for (uint32_t i = 0; i < num_points; i++)
150  {
151  PointCloud::Point& current_point = points[i];
152  current_point.position.x = msg->cells[i].x;
153  current_point.position.y = msg->cells[i].y;
154  current_point.position.z = msg->cells[i].z;
155  current_point.color = color_int;
156  }
157 
158  cloud_->clear();
159 
160  if (!points.empty())
161  {
162  cloud_->addPoints(&points.front(), points.size());
163  }
164 }
165 
166 } // namespace rviz
167 
rviz::PointCloud
A visual representation of a set of points.
Definition: point_cloud.h:108
rviz::MessageFilterDisplay< nav_msgs::GridCells >
rviz::GridCellsDisplay::GridCellsDisplay
GridCellsDisplay()
Definition: grid_cells_display.cpp:48
rviz::GridCellsDisplay::alpha_property_
FloatProperty * alpha_property_
Definition: grid_cells_display.h:75
rviz::ColorProperty::getColor
virtual QColor getColor() const
Definition: color_property.h:79
rviz::MessageFilterDisplay< nav_msgs::GridCells >::reset
void reset() override
Definition: message_filter_display.h:125
validate_floats.h
rviz::qtToOgre
Ogre::ColourValue qtToOgre(const QColor &c)
Definition: parse_color.cpp:83
frame_manager.h
rviz::DisplayContext::queueRender
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
rviz::MessageFilterDisplay< nav_msgs::GridCells >::unsubscribe
virtual void unsubscribe()
Definition: message_filter_display.h:177
rviz::PointCloud::setAlpha
void setAlpha(float alpha, bool per_point_alpha=false)
Definition: point_cloud.cpp:368
rviz::Display::initialized
bool initialized() const
Returns true if the display has been initialized.
Definition: display.h:275
rviz::StatusProperty::Error
@ Error
Definition: status_property.h:46
rviz::PointCloud::addPoints
void addPoints(Point *points, uint32_t num_points)
Add points to this point cloud.
Definition: point_cloud.cpp:400
rviz::FloatProperty::setMax
void setMax(float max)
Definition: float_property.cpp:57
rviz::GridCellsDisplay::cloud_
PointCloud * cloud_
Definition: grid_cells_display.h:72
rviz::validateFloats
bool validateFloats(const sensor_msgs::CameraInfo &msg)
Definition: camera_display.cpp:72
point_cloud.h
float_property.h
rviz::Display::fixed_frame_
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:312
rviz::FloatProperty::setMin
void setMin(float min)
Definition: float_property.cpp:51
rviz::GridCellsDisplay::reset
void reset() override
Called to tell the display to clear its state.
Definition: grid_cells_display.cpp:85
rviz::ColorProperty
Definition: color_property.h:40
rviz::Display
Definition: display.h:63
rviz::PointCloud::Point
Representation of a point, with x/y/z position and r/g/b color.
Definition: point_cloud.h:133
rviz::FloatProperty
Property specialized to enforce floating point max/min.
Definition: float_property.h:37
rviz::Display::setStatus
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
Definition: display.cpp:176
rviz::GridCellsDisplay::onInitialize
void onInitialize() override
Override this function to do subclass-specific initialization.
Definition: grid_cells_display.cpp:58
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rviz::FloatProperty::getFloat
virtual float getFloat() const
Definition: float_property.h:79
rviz::PointCloud::Point::color
Ogre::ColourValue color
Definition: point_cloud.h:141
rviz::GridCellsDisplay::color_property_
ColorProperty * color_property_
Definition: grid_cells_display.h:74
ROS_DEBUG
#define ROS_DEBUG(...)
rviz::GridCellsDisplay
Displays a nav_msgs::GridCells message.
Definition: grid_cells_display.h:56
rviz
Definition: add_display_dialog.cpp:54
rviz::Display::scene_node_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:295
color_property.h
arrow.h
rviz::DisplayContext::getFrameManager
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
rviz::PointCloud::setDimensions
void setDimensions(float width, float height, float depth)
Set the dimensions of the billboards used to render each point.
Definition: point_cloud.cpp:300
rviz::PointCloud::setRenderMode
void setRenderMode(RenderMode mode)
Set what type of rendering primitives should be used, currently points, billboards and boxes are supp...
Definition: point_cloud.cpp:218
rviz::GridCellsDisplay::updateAlpha
void updateAlpha()
Definition: grid_cells_display.cpp:91
rviz::PointCloud::RM_TILES
@ RM_TILES
Definition: point_cloud.h:117
rviz::GridCellsDisplay::~GridCellsDisplay
~GridCellsDisplay() override
Definition: grid_cells_display.cpp:74
rviz::MessageFilterDisplay< nav_msgs::GridCells >::onInitialize
void onInitialize() override
Definition: message_filter_display.h:105
rviz::FrameManager::getTransform
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Return the pose for a header, relative to the fixed frame, in Ogre classes.
Definition: frame_manager.h:125
rviz::PointCloud::Point::position
Ogre::Vector3 position
Definition: point_cloud.h:140
rviz::Display::context_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
Definition: display.h:287
rviz::PointCloud::clear
void clear()
Clear all the points.
Definition: point_cloud.cpp:164
class_list_macros.hpp
rviz::GridCellsDisplay::last_frame_count_
uint64_t last_frame_count_
Definition: grid_cells_display.h:77
display_context.h
rviz::DisplayContext::getFrameCount
virtual uint64_t getFrameCount() const =0
Return the current value of the frame count.
grid_cells_display.h
rviz::GridCellsDisplay::processMessage
void processMessage(const nav_msgs::GridCells::ConstPtr &msg) override
Definition: grid_cells_display.cpp:106
rviz::PointCloud::setCommonDirection
void setCommonDirection(const Ogre::Vector3 &vec)
See Ogre::BillboardSet::setCommonDirection.
Definition: point_cloud.cpp:326
rviz::PointCloud::setCommonUpVector
void setCommonUpVector(const Ogre::Vector3 &vec)
See Ogre::BillboardSet::setCommonUpVector.
Definition: point_cloud.cpp:338
parse_color.h


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:53