vector3_display.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, 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 
31 #include <boost/bind.hpp>
32 
33 #include <tf/transform_listener.h>
34 
35 #include "rviz/frame_manager.h"
42 #include "rviz/validate_floats.h"
43 #include "rviz/display_context.h"
44 
45 #include "vector3_display.h"
46 
48 {
49 
51  : Display()
52  , messages_received_( 0 )
53 {
54  topic_property_ = new RosTopicProperty( "Topic", "",
55  QString::fromStdString( ros::message_traits::datatype<geometry_msgs::Vector3Stamped>() ),
56  "geometry_msgs::Vector3Stamped topic to subscribe to.",
57  this, SLOT( updateTopic() ));
58 
59  color_property_ = new ColorProperty( "Color", QColor( 0, 25, 255 ),
60  "Color of the arrows.",
61  this, SLOT( updateColor() ));
62 
63  origin_frame_property_ = new TfFrameProperty( "Origin Frame", "base_link",
64  "Frame that defines the origin of the vector.",
65  this,
66  0, true,
67  SLOT( updateOriginFrame() ));
68 
69  position_tolerance_property_ = new FloatProperty( "Position Tolerance", .1,
70  "Distance, in meters from the last arrow dropped, "
71  "that will cause a new arrow to drop.",
72  this );
74 
75  angle_tolerance_property_ = new FloatProperty( "Angle Tolerance", .1,
76  "Angular distance from the last arrow dropped, "
77  "that will cause a new arrow to drop.",
78  this );
80 
81  scale_property_ = new FloatProperty( "Scale", 1.0,
82  "Scale of each arrow.",
83  this, SLOT( updateScale() ));
84 
85  keep_property_ = new IntProperty( "Keep", 100,
86  "Number of arrows to keep before removing the oldest. 0 means keep all of them.",
87  this );
88  keep_property_->setMin( 0 );
89 }
90 
92 {
93  unsubscribe();
94  clear();
95  delete tf_filter_;
96 }
97 
99 {
101  5, update_nh_ );
102 
104  tf_filter_->registerCallback( boost::bind( &Vector3Display::incomingMessage, this, _1 ));
106 
108 }
109 
110 // Clear the visuals by deleting their objects.
112 {
113  D_Arrow::iterator it = arrows_.begin();
114  D_Arrow::iterator end = arrows_.end();
115  for ( ; it != end; ++it )
116  {
117  delete *it;
118  }
119  arrows_.clear();
120 
121  last_position_.reset();
122  last_orientation_.reset();
123 
124  tf_filter_->clear();
125 
126  messages_received_ = 0;
127  setStatus( StatusProperty::Warn, "Topic", "No messages received" );
128 }
129 
131 {
132  unsubscribe();
133  clear();
134  subscribe();
136 }
137 
139 {
140  QColor color = color_property_->getColor();
141  float red = color.redF();
142  float green = color.greenF();
143  float blue = color.blueF();
144 
145  D_Arrow::iterator it = arrows_.begin();
146  D_Arrow::iterator end = arrows_.end();
147  for( ; it != end; ++it )
148  {
149  Arrow* arrow = *it;
150  arrow->setColor( red, green, blue, 1.0f );
151  }
153 }
154 
156 {
157 
158 }
159 
161 {
162 
163 }
164 
166 {
167  if ( !isEnabled() )
168  {
169  return;
170  }
171 
172  try
173  {
175  setStatus( StatusProperty::Ok, "Topic", "OK" );
176  }
177  catch( ros::Exception& e )
178  {
179  setStatus( StatusProperty::Error, "Topic", QString( "Error subscribing: " ) + e.what() );
180  }
181 }
182 
184 {
185  sub_.unsubscribe();
186 }
187 
189 {
190  subscribe();
191 }
192 
194 {
195  unsubscribe();
196  clear();
197 }
198 
199 // This is our callback to handle an incoming message.
200 void Vector3Display::incomingMessage( const geometry_msgs::Vector3Stamped::ConstPtr& message )
201 {
203 
204  if( !validateFloats( message->vector ))
205  {
206  setStatus( StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)" );
207  return;
208  }
209 
210  setStatus( StatusProperty::Ok, "Topic", QString::number( messages_received_ ) + " messages received" );
211 
212  // Here we call the rviz::FrameManager to get the transform from the
213  // fixed frame to the frame in the header of this Vector3 message. If
214  // it fails, we can't do anything else so we return.
215  Ogre::Quaternion orientation, fake_orientation;
216  Ogre::Vector3 position, fake_position;
218  message->header.stamp,
219  position, fake_orientation ))
220  {
221  ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'",
222  qPrintable( origin_frame_property_->getString() ), qPrintable( fixed_frame_ ) );
223  return;
224  }
225 
226  if( !context_->getFrameManager()->getTransform( message->header.frame_id,
227  message->header.stamp,
228  fake_position, orientation ))
229  {
230  ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'",
231  message->header.frame_id.c_str(), qPrintable( fixed_frame_ ) );
232  return;
233  }
234 
235  Ogre::Vector3 vector( message->vector.x, message->vector.y, -message->vector.z );
236  orientation = orientation * vector.getRotationTo(Ogre::Vector3::UNIT_Z);
237 
239  {
240  if( (*last_position_ - position).length() < position_tolerance_property_->getFloat() &&
241  (*last_orientation_ - orientation).normalise() < angle_tolerance_property_->getFloat() )
242  {
243  return;
244  }
245  }
246 
247  float length = vector.length();
248  Arrow* arrow = new Arrow( scene_manager_, scene_node_, std::max(length - 0.2f, 0.0f), 0.05f, 0.2f, 0.2f );
249 
250  arrow->setPosition(position);
251  arrow->setOrientation(orientation);
252 
253  QColor color = color_property_->getColor();
254  arrow->setColor( color.redF(), color.greenF(), color.blueF(), 1.0f );
255 
256  Ogre::Vector3 scale(scale_property_->getFloat());
257  arrow->setScale( scale );
258 
259  arrows_.push_back( arrow );
260 
261  if (!last_position_) last_position_.reset(new Ogre::Vector3());
262  if (!last_orientation_) last_orientation_.reset(new Ogre::Quaternion());
263  *last_position_ = position;
264  *last_orientation_ = orientation;
266 }
267 
269 {
270  tf_filter_->setTargetFrame( fixed_frame_.toStdString() );
271  clear();
272 }
273 
274 void Vector3Display::update( float wall_dt, float ros_dt )
275 {
276  size_t keep = keep_property_->getInt();
277  if( keep > 0 )
278  {
279  while( arrows_.size() > keep )
280  {
281  delete arrows_.front();
282  arrows_.pop_front();
283  }
284  }
285 }
286 
288 {
289  Display::reset();
290  clear();
291 }
292 
293 } // namespace hector_rviz_plugins
294 
virtual QColor getColor() const
void setMin(float min)
void connectInput(F &f)
f
virtual tf::TransformListener * getTFClient() const =0
DisplayContext * context_
message_filters::Subscriber< geometry_msgs::Vector3Stamped > sub_
virtual int getInt() const
ros::NodeHandle update_nh_
virtual float getFloat() const
void setMin(int min)
virtual void update(float wall_dt, float ros_dt)
boost::shared_ptr< Ogre::Quaternion > last_orientation_
Ogre::SceneNode * scene_node_
boost::shared_ptr< Ogre::Vector3 > last_position_
std::string getStdString()
bool isEnabled() const
QString fixed_frame_
virtual void setPosition(const Ogre::Vector3 &position)
bool validateFloats(const sensor_msgs::CameraInfo &msg)
virtual void setScale(const Ogre::Vector3 &scale)
virtual void reset()
void registerFilterForTransformStatusCheck(tf::MessageFilter< M > *filter, Display *display)
virtual void setColor(float r, float g, float b, float a)
virtual FrameManager * getFrameManager() const =0
virtual void setOrientation(const Ogre::Quaternion &orientation)
void incomingMessage(const geometry_msgs::Vector3Stamped::ConstPtr &message)
Ogre::SceneManager * scene_manager_
virtual void queueRender()=0
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void setFrameManager(FrameManager *frame_manager)
void setTargetFrame(const std::string &target_frame)
std::string getTopicStd() const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
tf::MessageFilter< geometry_msgs::Vector3Stamped > * tf_filter_
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Connection registerCallback(const C &callback)
#define ROS_DEBUG(...)


hector_rviz_plugins
Author(s): Johannes Meyer
autogenerated on Mon Jun 10 2019 13:36:38