effort_display.h
Go to the documentation of this file.
1 #ifndef EFFORT_DISPLAY_H
2 #define EFFORT_DISPLAY_H
3 
4 #ifndef Q_MOC_RUN
5 #include <boost/circular_buffer.hpp>
6 #endif
7 
8 #include <sensor_msgs/JointState.h>
10 
11 namespace Ogre
12 {
13  class SceneNode;
14 }
15 
16 namespace rviz
17 {
18  class FloatProperty;
19  class IntProperty;
20  class StringProperty;
21  class CategoryProperty;
22  class BoolProperty;
23  class RosTopicProperty;
24 }
25 
26 namespace urdf
27 {
28  class Model;
29 }
30 
31 // MessageFilter to support message with out frame_id
32 // https://code.ros.org/trac/ros-pkg/ticket/5467
33 namespace tf
34 {
35 #ifdef TF_MESSAGEFILTER_DEBUG
36 # undef TF_MESSAGEFILTER_DEBUG
37 #endif
38 #define TF_MESSAGEFILTER_DEBUG(fmt, ...) \
39  ROS_DEBUG_NAMED("message_filter", "MessageFilter [target=%s]: " fmt, getTargetFramesString().c_str(), __VA_ARGS__)
40 
41 #ifdef TF_MESSAGEFILTER_WARN
42 # undef TF_MESSAGEFILTER_WARN
43 #endif
44 #define TF_MESSAGEFILTER_WARN(fmt, ...) \
45  ROS_WARN_NAMED("message_filter", "MessageFilter [target=%s]: " fmt, getTargetFramesString().c_str(), __VA_ARGS__)
46 
47  class MessageFilterJointState : public MessageFilter<sensor_msgs::JointState>
48  {
49  typedef sensor_msgs::JointState M;
50 public:
53  typedef boost::function<void(const MConstPtr&, FilterFailureReason)> FailureCallback;
54 #ifdef RVIZ_USE_BOOST_SIGNAL_1
55  typedef boost::signal<void(const MConstPtr&, FilterFailureReason)> FailureSignal;
56 #else
57  typedef boost::signals2::signal<void(const MConstPtr&, FilterFailureReason)> FailureSignal;
58 #endif
59 
60  // If you hit this assert your message does not have a header, or does not have the HasHeader trait defined for it
62 
72  MessageFilterJointState(Transformer& tf, const std::string& target_frame, uint32_t queue_size, ros::NodeHandle nh = ros::NodeHandle(), ros::Duration max_rate = ros::Duration(0.01))
73  : MessageFilter<sensor_msgs::JointState>(tf, target_frame, queue_size, nh, max_rate)
74  , tf_(tf)
75  , nh_(nh)
76  , max_rate_(max_rate)
77  , queue_size_(queue_size)
78  {
79  init();
80 
81  setTargetFrame(target_frame);
82  }
83 
94  template<class F>
95  MessageFilterJointState(F& f, Transformer& tf, const std::string& target_frame, uint32_t queue_size, ros::NodeHandle nh = ros::NodeHandle(), ros::Duration max_rate = ros::Duration(0.01))
96  : tf_(tf)
97  , nh_(nh)
98  , max_rate_(max_rate)
99  , queue_size_(queue_size)
100  , MessageFilter<sensor_msgs::JointState>(f, tf, target_frame, queue_size, nh, max_rate)
101  {
102  init();
103 
104  setTargetFrame(target_frame);
105 
106  connectInput(f);
107  }
108 
112  template<class F>
113  void connectInput(F& f)
114  {
115  message_connection_.disconnect();
116  message_connection_ = f.registerCallback(&MessageFilterJointState::incomingMessage, this);
117  }
118 
123  {
124  message_connection_.disconnect();
125  tf_.removeTransformsChangedListener(tf_connection_);
126 
127  clear();
128 
129  TF_MESSAGEFILTER_DEBUG("Successful Transforms: %llu, Failed Transforms: %llu, Discarded due to age: %llu, Transform messages received: %llu, Messages received: %llu, Total dropped: %llu",
130  (long long unsigned int)successful_transform_count_, (long long unsigned int)failed_transform_count_,
131  (long long unsigned int)failed_out_the_back_count_, (long long unsigned int)transform_message_count_,
132  (long long unsigned int)incoming_message_count_, (long long unsigned int)dropped_message_count_);
133 
134  }
135 
139  void setTargetFrame(const std::string& target_frame)
140  {
141  std::vector<std::string> frames;
142  frames.push_back(target_frame);
143  setTargetFrames(frames);
144  }
145 
149  void setTargetFrames(const std::vector<std::string>& target_frames)
150  {
151  boost::mutex::scoped_lock list_lock(messages_mutex_);
152  boost::mutex::scoped_lock string_lock(target_frames_string_mutex_);
153 
154  target_frames_ = target_frames;
155 
156  std::stringstream ss;
157  for (std::vector<std::string>::iterator it = target_frames_.begin(); it != target_frames_.end(); ++it)
158  {
159  *it = tf::resolve(tf_.getTFPrefix(), *it);
160  ss << *it << " ";
161  }
162  target_frames_string_ = ss.str();
163  }
167  std::string getTargetFramesString()
168  {
169  boost::mutex::scoped_lock lock(target_frames_string_mutex_);
170  return target_frames_string_;
171  };
172 
176  void setTolerance(const ros::Duration& tolerance)
177  {
178  time_tolerance_ = tolerance;
179  }
180 
184  void clear()
185  {
186  boost::mutex::scoped_lock lock(messages_mutex_);
187 
188  TF_MESSAGEFILTER_DEBUG("%s", "Cleared");
189 
190  messages_.clear();
191  message_count_ = 0;
192 
193  warned_about_unresolved_name_ = false;
194  warned_about_empty_frame_id_ = false;
195  }
196 
197  void add(const MEvent& evt)
198  {
199  boost::mutex::scoped_lock lock(messages_mutex_);
200 
201  testMessages();
202 
203  if (!testMessage(evt))
204  {
205  // If this message is about to push us past our queue size, erase the oldest message
206  if (queue_size_ != 0 && message_count_ + 1 > queue_size_)
207  {
208  ++dropped_message_count_;
209  const MEvent& front = messages_.front();
210  TF_MESSAGEFILTER_DEBUG("Removed oldest message because buffer is full, count now %d (frame_id=%s, stamp=%f)", message_count_, front.getMessage()->header.frame_id.c_str(), front.getMessage()->header.stamp.toSec());
211  signalFailure(messages_.front(), filter_failure_reasons::Unknown);
212 
213  messages_.pop_front();
214  --message_count_;
215  }
216 
217  // Add the message to our list
218  messages_.push_back(evt);
219  ++message_count_;
220  }
221 
222  TF_MESSAGEFILTER_DEBUG("Added message in frame %s at time %.3f, count now %d", evt.getMessage()->header.frame_id.c_str(), evt.getMessage()->header.stamp.toSec(), message_count_);
223 
224  ++incoming_message_count_;
225  }
226 
232  void add(const MConstPtr& message)
233  {
234  boost::shared_ptr<std::map<std::string, std::string> > header(new std::map<std::string, std::string>);
235  (*header)["callerid"] = "unknown";
236  add(MEvent(message, header, ros::Time::now()));
237  }
238 
243  message_filters::Connection registerFailureCallback(const FailureCallback& callback)
244  {
245  boost::mutex::scoped_lock lock(failure_signal_mutex_);
246  return message_filters::Connection(boost::bind(&MessageFilterJointState::disconnectFailure, this, _1), failure_signal_.connect(callback));
247  }
248 
249  virtual void setQueueSize( uint32_t new_queue_size )
250  {
251  queue_size_ = new_queue_size;
252  }
253 
254  virtual uint32_t getQueueSize()
255  {
256  return queue_size_;
257  }
258 
259  private:
260 
261  void init()
262  {
263  message_count_ = 0;
264  new_transforms_ = false;
265  successful_transform_count_ = 0;
266  failed_transform_count_ = 0;
267  failed_out_the_back_count_ = 0;
268  transform_message_count_ = 0;
269  incoming_message_count_ = 0;
270  dropped_message_count_ = 0;
271  time_tolerance_ = ros::Duration(0.0);
272  warned_about_unresolved_name_ = false;
273  warned_about_empty_frame_id_ = false;
274 
275  tf_connection_ = tf_.addTransformsChangedListener(boost::bind(&MessageFilterJointState::transformsChanged, this));
276 
277  max_rate_timer_ = nh_.createTimer(max_rate_, &MessageFilterJointState::maxRateTimerCallback, this);
278  }
279 
280  typedef std::list<MEvent> L_Event;
281 
282  bool testMessage(const MEvent& evt)
283  {
284  const MConstPtr& message = evt.getMessage();
285  std::string callerid = evt.getPublisherName();
286  std::string frame_id = ros::message_traits::FrameId<M>::value(*message);
288 
289  // FIXED
290  if (frame_id.empty()) frame_id = * (target_frames_.begin());
291  //Throw out messages which have an empty frame_id
292  if (frame_id.empty())
293  {
294  if (!warned_about_empty_frame_id_)
295  {
296  warned_about_empty_frame_id_ = true;
297  TF_MESSAGEFILTER_WARN("Discarding message from [%s] due to empty frame_id. This message will only print once.", callerid.c_str());
298  }
299  signalFailure(evt, filter_failure_reasons::EmptyFrameID);
300  return true;
301  }
302 
303  if (frame_id[0] != '/')
304  {
305  std::string unresolved = frame_id;
306  frame_id = tf::resolve(tf_.getTFPrefix(), frame_id);
307 
308  if (!warned_about_unresolved_name_)
309  {
310  warned_about_unresolved_name_ = true;
311  ROS_WARN("Message from [%s] has a non-fully-qualified frame_id [%s]. Resolved locally to [%s]. This is will likely not work in multi-robot systems. This message will only print once.", callerid.c_str(), unresolved.c_str(), frame_id.c_str());
312  }
313  }
314 
315  //Throw out messages which are too old
317  for (std::vector<std::string>::iterator target_it = target_frames_.begin(); target_it != target_frames_.end(); ++target_it)
318  {
319  const std::string& target_frame = *target_it;
320 
321  if (target_frame != frame_id && stamp != ros::Time(0))
322  {
323  ros::Time latest_transform_time ;
324 
325  tf_.getLatestCommonTime(frame_id, target_frame, latest_transform_time, 0) ;
326  if (stamp + tf_.getCacheLength() < latest_transform_time)
327  {
328  ++failed_out_the_back_count_;
329  ++dropped_message_count_;
330  TF_MESSAGEFILTER_DEBUG("Discarding Message, in frame %s, Out of the back of Cache Time(stamp: %.3f + cache_length: %.3f < latest_transform_time %.3f. Message Count now: %d", message->header.frame_id.c_str(), message->header.stamp.toSec(), tf_.getCacheLength().toSec(), latest_transform_time.toSec(), message_count_);
331 
332  last_out_the_back_stamp_ = stamp;
333  last_out_the_back_frame_ = frame_id;
334 
335  signalFailure(evt, filter_failure_reasons::OutTheBack);
336  return true;
337  }
338  }
339 
340  }
341 
342  bool ready = !target_frames_.empty();
343  for (std::vector<std::string>::iterator target_it = target_frames_.begin(); ready && target_it != target_frames_.end(); ++target_it)
344  {
345  std::string& target_frame = *target_it;
346  if (time_tolerance_ != ros::Duration(0.0))
347  {
348  ready = ready && (tf_.canTransform(target_frame, frame_id, stamp) &&
349  tf_.canTransform(target_frame, frame_id, stamp + time_tolerance_) );
350  }
351  else
352  {
353  ready = ready && tf_.canTransform(target_frame, frame_id, stamp);
354  }
355  }
356 
357  if (ready)
358  {
359  TF_MESSAGEFILTER_DEBUG("Message ready in frame %s at time %.3f, count now %d", frame_id.c_str(), stamp.toSec(), message_count_);
360 
361  ++successful_transform_count_;
362 
363  signalMessage(evt);
364  }
365  else
366  {
367  ++failed_transform_count_;
368  }
369 
370  return ready;
371  }
372 
374  {
375  if (!messages_.empty() && getTargetFramesString() == " ")
376  {
377  ROS_WARN_NAMED("message_notifier", "MessageFilter [target=%s]: empty target frame", getTargetFramesString().c_str());
378  }
379 
380  int i = 0;
381 
382  L_Event::iterator it = messages_.begin();
383  for (; it != messages_.end(); ++i)
384  {
385  MEvent& evt = *it;
386 
387  if (testMessage(evt))
388  {
389  --message_count_;
390  it = messages_.erase(it);
391  }
392  else
393  {
394  ++it;
395  }
396  }
397  }
398 
400  {
401  boost::mutex::scoped_lock list_lock(messages_mutex_);
402  if (new_transforms_)
403  {
404  testMessages();
405  new_transforms_ = false;
406  }
407 
408  checkFailures();
409  }
410 
415  {
416  add(evt);
417  }
418 
420  {
421  new_transforms_ = true;
422 
423  ++transform_message_count_;
424  }
425 
427  {
428  if (next_failure_warning_.isZero())
429  {
430  next_failure_warning_ = ros::Time::now() + ros::Duration(15);
431  }
432 
433  if (ros::Time::now() >= next_failure_warning_)
434  {
435  if (incoming_message_count_ - message_count_ == 0)
436  {
437  return;
438  }
439 
440  double dropped_pct = (double)dropped_message_count_ / (double)(incoming_message_count_ - message_count_);
441  if (dropped_pct > 0.95)
442  {
443  TF_MESSAGEFILTER_WARN("Dropped %.2f%% of messages so far. Please turn the [%s.message_notifier] rosconsole logger to DEBUG for more information.", dropped_pct*100, ROSCONSOLE_DEFAULT_NAME);
444  next_failure_warning_ = ros::Time::now() + ros::Duration(60);
445 
446  if ((double)failed_out_the_back_count_ / (double)dropped_message_count_ > 0.5)
447  {
448  TF_MESSAGEFILTER_WARN(" The majority of dropped messages were due to messages growing older than the TF cache time. The last message's timestamp was: %f, and the last frame_id was: %s", last_out_the_back_stamp_.toSec(), last_out_the_back_frame_.c_str());
449  }
450  }
451  }
452  }
453 
455  {
456  boost::mutex::scoped_lock lock(failure_signal_mutex_);
457  c.getBoostConnection().disconnect();
458  }
459 
460  void signalFailure(const MEvent& evt, FilterFailureReason reason)
461  {
462  boost::mutex::scoped_lock lock(failure_signal_mutex_);
463  failure_signal_(evt.getMessage(), reason);
464  }
465 
470  std::vector<std::string> target_frames_;
473  uint32_t queue_size_;
474 
475  L_Event messages_;
476  uint32_t message_count_;
477  boost::mutex messages_mutex_;
478 
480  volatile bool new_transforms_;
481 
484 
491 
494 
496 
498 
499 #ifdef RVIZ_USE_BOOST_SIGNAL_1
500  boost::signals::connection tf_connection_;
501 #else
502  boost::signals2::connection tf_connection_;
503 #endif
505 
506  FailureSignal failure_signal_;
507  boost::mutex failure_signal_mutex_;
508  };
509 }
510 
511 #ifndef Q_MOC_RUN
513 #include <tf/message_filter.h>
514 #endif
515 
516 #include "rviz/display_context.h"
517 #include "rviz/frame_manager.h"
519 
520 namespace rviz
521 {
529 {
530 // No Q_OBJECT macro here, moc does not support Q_OBJECT in a templated class.
531 public:
535 
537  : tf_filter_( NULL )
538  , messages_received_( 0 )
539  {
540  QString message_type = QString::fromStdString( ros::message_traits::datatype<sensor_msgs::JointState>() );
541  topic_property_->setMessageType( message_type );
542  topic_property_->setDescription( message_type + " topic to subscribe to." );
543  }
544 
545  virtual void onInitialize()
546  {
547  tf_filter_ = new tf::MessageFilterJointState( *context_->getTFClient(),
548  fixed_frame_.toStdString(), 10, update_nh_ );
549 
550  tf_filter_->connectInput( sub_ );
551  tf_filter_->registerCallback( boost::bind( &MessageFilterJointStateDisplay::incomingMessage, this, _1 ));
552  context_->getFrameManager()->registerFilterForTransformStatusCheck( tf_filter_, this );
553  }
554 
556  {
557  unsubscribe();
558  delete tf_filter_;
559  }
560 
561  virtual void reset()
562  {
563  Display::reset();
564  tf_filter_->clear();
565  messages_received_ = 0;
566  }
567 
568 protected:
569  virtual void updateTopic()
570  {
571  unsubscribe();
572  reset();
573  subscribe();
574  context_->queueRender();
575  }
576 
577  virtual void subscribe()
578  {
579  if( !isEnabled() )
580  {
581  return;
582  }
583 
584  try
585  {
586  sub_.subscribe( update_nh_, topic_property_->getTopicStd(), 10 );
587  setStatus( StatusProperty::Ok, "Topic", "OK" );
588  }
589  catch( ros::Exception& e )
590  {
591  setStatus( StatusProperty::Error, "Topic", QString( "Error subscribing: " ) + e.what() );
592  }
593  }
594 
595  virtual void unsubscribe()
596  {
597  sub_.unsubscribe();
598  }
599 
600  virtual void onEnable()
601  {
602  subscribe();
603  }
604 
605  virtual void onDisable()
606  {
607  unsubscribe();
608  reset();
609  }
610 
611  virtual void fixedFrameChanged()
612  {
613  tf_filter_->setTargetFrame( fixed_frame_.toStdString() );
614  reset();
615  }
616 
620  void incomingMessage( const sensor_msgs::JointState::ConstPtr& msg )
621  {
622  if( !msg )
623  {
624  return;
625  }
626 
627  ++messages_received_;
628  setStatus( StatusProperty::Ok, "Topic", QString::number( messages_received_ ) + " messages received" );
629 
630  processMessage( msg );
631  }
632 
636  virtual void processMessage( const sensor_msgs::JointState::ConstPtr& msg ) = 0;
637 
641 };
642 } // rviz
643 
644 namespace rviz
645 {
646  class JointInfo: public QObject {
647  Q_OBJECT
648  public:
649  JointInfo(const std::string name, rviz::Property* parent_category);
650  ~JointInfo();
651 
652  void setEffort(double e);
653  double getEffort();
654  void setMaxEffort(double m);
655  double getMaxEffort();
656  bool getEnabled() const;
657 
659 
660  public Q_SLOTS:
661  void updateVisibility();
662 
663  private:
664  std::string name_;
665  double effort_, max_effort_;
666 
670  };
671 
672  typedef std::set<JointInfo*> S_JointInfo;
673  typedef std::vector<std::string> V_string;
674 
675  class EffortVisual;
676 
678  {
679  Q_OBJECT
680  public:
681  // Constructor. pluginlib::ClassLoader creates instances by calling
682  // the default constructor, so make sure you have one.
683  EffortDisplay();
684  virtual ~EffortDisplay();
685 
686  // Overrides of public virtual functions from the Display class.
687  virtual void onInitialize();
688  virtual void reset();
689 
690  private Q_SLOTS:
691  // Helper function to apply color and alpha to all visuals.
692  void updateColorAndAlpha();
693  void updateHistoryLength();
694  void updateRobotDescription();
695 
696  JointInfo* getJointInfo( const std::string& joint);
697  JointInfo* createJoint(const std::string &joint);
698 
699  protected:
700  // overrides from Display
701  virtual void onEnable();
702  virtual void onDisable();
703 
704  // load
705  void load();
706  void clear();
707 
708  // The object for urdf model
710 
711  //
712  std::string robot_description_;
713 
714  private:
715  void processMessage( const sensor_msgs::JointState::ConstPtr& msg );
716 
717  // Storage for the list of visuals. It is a circular buffer where
718  // data gets popped from the front (oldest) and pushed to the back (newest)
719  boost::circular_buffer<boost::shared_ptr<EffortVisual> > visuals_;
720 
721  typedef std::map<std::string, JointInfo*> M_JointInfo;
722  M_JointInfo joints_;
723 
724  // Property objects for user-editable properties.
725  rviz::FloatProperty *alpha_property_,* width_property_,* scale_property_;
727 
731  };
732 } // end namespace rviz_plugin_tutorials
733 
734 #endif // EFFORT_DISPLAY_H
virtual uint32_t getQueueSize()
#define NULL
Definition: global.h:37
uint32_t message_count_
The number of messages in the list. Used because messages_.size() has linear cost.
message_filters::Subscriber< sensor_msgs::JointState > sub_
void add(const MConstPtr &message)
Manually add a message into this filter.
rviz::BoolProperty * all_enabled_property_
std::list< MEvent > L_Event
rviz::IntProperty * history_length_property_
virtual void setQueueSize(uint32_t new_queue_size)
boost::shared_ptr< M const > MConstPtr
bool testMessage(const MEvent &evt)
rviz::StringProperty * robot_description_property_
#define ROS_WARN_NAMED(name,...)
tf::MessageFilterJointState * tf_filter_
message_filters::Connection message_connection_
Display subclass using a tf::MessageFilter, templated on the ROS message type.
virtual void onDisable()
Derived classes override this to do the actual work of disabling themselves.
rviz::Property * joints_category_
Transformer & tf_
The Transformer used to determine if transformation data is available.
A single element of a property tree, with a name, value, description, and possibly children...
Definition: property.h:100
void setTargetFrames(const std::vector< std::string > &target_frames)
Set the frames you need to be able to transform to before getting a message callback.
virtual void onEnable()
Derived classes override this to do the actual work of enabling themselves.
void setTolerance(const ros::Duration &tolerance)
Set the required tolerance for the notifier to return true.
std::string name_
ros::Time last_update_
#define TF_MESSAGEFILTER_WARN(fmt,...)
MessageFilterJointState(Transformer &tf, const std::string &target_frame, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle(), ros::Duration max_rate=ros::Duration(0.01))
Constructor.
uint32_t queue_size_
The maximum number of messages we queue up.
std::map< std::string, JointInfo * > M_JointInfo
bool add(const actionlib::TwoIntsGoal &req, actionlib::TwoIntsResult &res)
Property specialized to enforce floating point max/min.
#define ROS_WARN(...)
void clear()
Clear any messages currently in the queue.
Property specialized to provide max/min enforcement for integers.
Definition: int_property.h:38
void disconnectFailure(const message_filters::Connection &c)
boost::signals2::connection getBoostConnection() const
boost::signals2::signal< void(const MConstPtr &, FilterFailureReason)> FailureSignal
boost::shared_ptr< urdf::Model > robot_model_
void connectInput(F &f)
Connect this filter&#39;s input to another filter&#39;s output. If this filter is already connected...
void incomingMessage(const sensor_msgs::JointState::ConstPtr &msg)
Incoming message callback. Checks if the message pointer is valid, increments messages_received_, then calls processMessage().
boost::function< void(const MConstPtr &, FilterFailureReason)> FailureCallback
std::string resolve(const std::string &prefix, const std::string &frame_name)
ros::NodeHandle nh_
The node used to subscribe to the topic.
const std::string & getPublisherName() const
boost::mutex target_frames_string_mutex_
void subscribe()
virtual void onInitialize()
Override this function to do subclass-specific initialization.
ros::Duration time_tolerance_
Provide additional tolerance on time for messages which are stamped but can have associated duration...
#define ROS_STATIC_ASSERT(cond)
rviz::FloatProperty * width_property_
std::string getTargetFramesString()
Get the target frames as a string for debugging.
~MessageFilterJointState()
Destructor.
MessageFilterJointStateDisplay MFDClass
Convenience typedef so subclasses don&#39;t have to use the long templated class name to refer to their s...
message_filters::Connection registerFailureCallback(const FailureCallback &callback)
Register a callback to be called when a message is about to be dropped.
virtual void reset()
Called to tell the display to clear its state.
rviz::FloatProperty * max_effort_property_
void incomingMessage(const ros::MessageEvent< M const > &evt)
Callback that happens when we receive a message on the message topic.
bool new_messages_
Used to skip waiting on new_data_ if new messages have come in while calling back.
void setTargetFrame(const std::string &target_frame)
Set the frame you need to be able to transform to before getting a message callback.
std::vector< std::string > V_string
boost::signals2::connection tf_connection_
void signalFailure(const MEvent &evt, FilterFailureReason reason)
#define TF_MESSAGEFILTER_DEBUG(fmt,...)
boost::circular_buffer< boost::shared_ptr< EffortVisual > > visuals_
Property specialized for string values.
Property specialized to provide getter for booleans.
Definition: bool_property.h:38
sensor_msgs::JointState M
rviz::FloatProperty * effort_property_
rviz::Property * category_
std::string robot_description_
static Time now()
boost::mutex messages_mutex_
The mutex used for locking message list operations.
volatile bool new_transforms_
Used to skip waiting on new_data_ if new transforms have come in while calling back or transforming d...
ros::MessageEvent< M const > MEvent
std::set< JointInfo * > S_JointInfo
MessageFilterJointState(F &f, Transformer &tf, const std::string &target_frame, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle(), ros::Duration max_rate=ros::Duration(0.01))
Constructor.
#define ROSCONSOLE_DEFAULT_NAME
std::vector< std::string > target_frames_
The frames we need to be able to transform to before a message is ready.
virtual void fixedFrameChanged()
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
void add(const MEvent &evt)
void maxRateTimerCallback(const ros::TimerEvent &)
boost::shared_ptr< M > getMessage() const
L_Event messages_
The message list.
Helper superclass for MessageFilterDisplay, needed because Qt&#39;s moc and c++ templates don&#39;t work nice...


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:50