SplineDisplay.cpp
Go to the documentation of this file.
1 /***************************************************************************
2  * Software License Agreement (BSD License) *
3  * Copyright (C) 2016 by George Todoran <george.todoran@tuwien.ac.at> *
4  * *
5  * Redistribution and use in source and binary forms, with or without *
6  * modification, are permitted provided that the following conditions *
7  * are met: *
8  * *
9  * 1. Redistributions of source code must retain the above copyright *
10  * notice, this list of conditions and the following disclaimer. *
11  * 2. Redistributions in binary form must reproduce the above copyright *
12  * notice, this list of conditions and the following disclaimer in *
13  * the documentation and/or other materials provided with the *
14  * distribution. *
15  * 3. Neither the name of the copyright holder nor the names of its *
16  * contributors may be used to endorse or promote products derived *
17  * from this software without specific prior written permission. *
18  * *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS *
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT *
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS *
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE *
23  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, *
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, *
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; *
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER *
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT *
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY *
29  * WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE *
30  * POSSIBILITY OF SUCH DAMAGE. *
31  ***************************************************************************/
32 
33 #include <OGRE/OgreSceneNode.h>
34 #include <OGRE/OgreSceneManager.h>
35 
36 #include <tf/transform_listener.h>
37 
42 #include <rviz/frame_manager.h>
43 
44 #include <Spline/SplineVisual.h>
45 #include <Spline/SplineDisplay.h>
46 
47 namespace tuw_nav_rviz_plugin {
48 
49 // The constructor must have no arguments, so we can't give the
50 // constructor the parameters it needs to fully initialize.
52  color_path_property_ = new rviz::ColorProperty ( "Path Color", QColor ( 50, 51, 204 ),
53  "Color to draw the spline.",
54  this, SLOT ( updatePathColor() ) );
55 
56  shape_property_ = new rviz::EnumProperty ( "Path Shape", QString::fromStdString ( "Sphere" ),
57  "Shape of the spline.",
58  this, SLOT ( updateShape() ) );
62 
63  points_nr_path_property_ = new rviz::IntProperty ( "Path Points Nr", 100,
64  "Number of points to display along path.",
65  this, SLOT ( updatePathPointsNr() ) );
67  points_nr_path_property_->setMax ( 100000 );
68 
69  scale_path_property_ = new rviz::FloatProperty ( "Path Points Scale", 0.1,
70  "Scale of the spline contour.",
71  this, SLOT ( updatePathScale() ) );
74 
75  color_orient_property_ = new rviz::ColorProperty ( "Orientation Color", QColor ( 50, 51, 204 ),
76  "Color to draw the spline orientation arrows.",
77  this, SLOT ( updateOrientColor() ) );
78  points_nr_orient_property_ = new rviz::IntProperty ( "Orientation Points Nr", 50,
79  "Number of arrows to display along path.",
80  this, SLOT ( updateOrientPointsNr() ) );
83 
84  scale_orient_property_ = new rviz::FloatProperty ( "Orientation Points Scale", 0.1,
85  "Scale of the spline orientation arrows.",
86  this, SLOT ( updateOrientScale() ) );
89 
90  history_length_property_ = new rviz::IntProperty ( "History Length", 1,
91  "Number of prior measurements to display.",
92  this, SLOT ( updateHistoryLength() ) );
94  history_length_property_->setMax ( 100000 );
95 }
96 
97 // After the top-level rviz::Display::initialize() does its own setup,
98 // it calls the subclass's onInitialize() function. This is where we
99 // instantiate all the workings of the class. We make sure to also
100 // call our immediate super-class's onInitialize() function, since it
101 // does important stuff setting up the message filter.
102 //
103 // Note that "MFDClass" is a typedef of
104 // ``MessageFilterDisplay<message type>``, to save typing that long
105 // templated class name every time you need to refer to the
106 // superclass.
110 }
111 
113 }
114 
115 // Clear the visuals by deleting their objects.
117  MFDClass::reset();
118  visuals_.clear();
119 }
120 
121 // Set the current color values for each visual.
123  Ogre::ColourValue color = color_path_property_->getOgreColor();
124  for ( auto& visualsI: visuals_ ) { visualsI->setPathColor ( color ); }
125 }
127  Ogre::ColourValue color = color_orient_property_->getOgreColor();
128  for ( auto& visualsI: visuals_ ) { visualsI->setOrientColor ( color ); }
129 }
130 
131 // Set the current shape for each visual.
134  for ( auto& visualsI: visuals_ ) { visualsI->setShape ( shape_type ); }
135 }
136 
137 // Set the current scale for each visual.
139  float scale = scale_path_property_->getFloat();
140  for ( auto& visualsI: visuals_ ) { visualsI->setPathScale ( scale ); }
141 }
143  float scale = scale_orient_property_->getFloat();
144  for ( auto& visualsI: visuals_ ) { visualsI->setOrientScale ( scale ); }
145 }
146 
147 // Set the number of past visuals to show.
149  visuals_.rset_capacity ( history_length_property_->getInt() );
150 }
151 
153  int pointsNr = points_nr_path_property_->getInt();
154  for ( auto& visualsI: visuals_ ) { visualsI->setPathPointsNr ( pointsNr ); }
155 }
157  int pointsNr = points_nr_orient_property_->getInt();
158  for ( auto& visualsI: visuals_ ) { visualsI->setOrientPointsNr ( pointsNr ); }
159 }
160 
161 
162 // This is our callback to handle an incoming message.
163 void SplineDisplay::processMessage ( const tuw_nav_msgs::Spline::ConstPtr& msg ) {
164  // Here we call the rviz::FrameManager to get the transform from the
165  // fixed frame to the frame in the header of this Imu message. If
166  // it fails, we can't do anything else so we return.
167  Ogre::Quaternion orientation;
168  Ogre::Vector3 position;
169  if ( !context_->getFrameManager()->getTransform ( msg->header.frame_id,
170  msg->header.stamp,
171  position, orientation ) ) {
172  ROS_DEBUG ( "Error transforming from frame '%s' to frame '%s'",
173  msg->header.frame_id.c_str(), qPrintable ( fixed_frame_ ) );
174  return;
175  }
176 
177  // We are keeping a circular buffer of visual pointers. This gets
178  // the next one, or creates and stores it if the buffer is not full
180  if ( visuals_.full() ) {
181  visual = visuals_.front();
182  } else {
183  visual.reset ( new SplineVisual ( context_->getSceneManager(), scene_node_ ) );
184  }
185 
186  // Now set or update the contents of the chosen visual.
187  visual->setMessage ( msg );
188  visual->setFramePosition ( position );
189  visual->setFrameOrientation ( orientation );
190 
191  visual->setPathColor ( color_path_property_->getOgreColor() );
192  visual->setShape ( ( rviz::Shape::Type ) shape_property_->getOptionInt() );
193  visual->setPathScale ( scale_path_property_->getFloat() );
194  visual->setPathPointsNr ( points_nr_path_property_->getInt() );
195 
196  visual->setOrientColor ( color_orient_property_->getOgreColor() );
197  visual->setOrientScale ( scale_orient_property_->getFloat() );
198  visual->setOrientPointsNr( points_nr_orient_property_->getInt() );
199 
200  // And send it to the end of the circular buffer
201  visuals_.push_back ( visual );
202 }
203 
204 } // end namespace tuw_nav_rviz_plugin
205 
206 // Tell pluginlib about this class. It is important to do this in
207 // global scope, outside our package's namespace.
void setMin(float min)
boost::circular_buffer< boost::shared_ptr< SplineVisual > > visuals_
void setMax(float max)
Ogre::ColourValue getOgreColor() const
DisplayContext * context_
rviz::ColorProperty * color_path_property_
virtual int getInt() const
rviz::EnumProperty * shape_property_
virtual float getFloat() const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void setMin(int min)
rviz::IntProperty * points_nr_orient_property_
Ogre::SceneNode * scene_node_
rviz::IntProperty * history_length_property_
void setMax(int max)
QString fixed_frame_
virtual FrameManager * getFrameManager() const =0
void addOptionStd(const std::string &option, int value=0)
rviz::FloatProperty * scale_path_property_
virtual Ogre::SceneManager * getSceneManager() const =0
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void processMessage(const tuw_nav_msgs::Spline::ConstPtr &msg)
rviz::ColorProperty * color_orient_property_
virtual int getOptionInt()
rviz::FloatProperty * scale_orient_property_
rviz::IntProperty * points_nr_path_property_
#define ROS_DEBUG(...)


tuw_nav_rviz_plugin
Author(s):
autogenerated on Sun Aug 28 2016 03:53:55