effort_display.h
Go to the documentation of this file.
00001 #ifndef EFFORT_DISPLAY_H
00002 #define EFFORT_DISPLAY_H
00003 
00004 #ifndef Q_MOC_RUN
00005 #include <boost/circular_buffer.hpp>
00006 #endif
00007 
00008 #include <sensor_msgs/JointState.h>
00009 #include <rviz/message_filter_display.h>
00010 
00011 namespace Ogre
00012 {
00013     class SceneNode;
00014 }
00015 
00016 namespace rviz
00017 {
00018     class FloatProperty;
00019     class IntProperty;
00020     class StringProperty;
00021     class CategoryProperty;
00022     class BoolProperty;
00023     class RosTopicProperty;
00024 }
00025 
00026 namespace urdf
00027 {
00028     class Model;
00029 }
00030 
00031 // MessageFilter to support message with out frame_id
00032 // https://code.ros.org/trac/ros-pkg/ticket/5467
00033 namespace tf
00034 {
00035 #ifdef TF_MESSAGEFILTER_DEBUG
00036 # undef TF_MESSAGEFILTER_DEBUG
00037 #endif
00038 #define TF_MESSAGEFILTER_DEBUG(fmt, ...) \
00039   ROS_DEBUG_NAMED("message_filter", "MessageFilter [target=%s]: " fmt, getTargetFramesString().c_str(), __VA_ARGS__)
00040 
00041 #ifdef TF_MESSAGEFILTER_WARN
00042 # undef TF_MESSAGEFILTER_WARN
00043 #endif
00044 #define TF_MESSAGEFILTER_WARN(fmt, ...) \
00045   ROS_WARN_NAMED("message_filter", "MessageFilter [target=%s]: " fmt, getTargetFramesString().c_str(), __VA_ARGS__)
00046 
00047     class MessageFilterJointState : public MessageFilter<sensor_msgs::JointState>
00048     {
00049         typedef sensor_msgs::JointState M;
00050 public:
00051         typedef boost::shared_ptr<M const> MConstPtr;
00052         typedef ros::MessageEvent<M const> MEvent;
00053         typedef boost::function<void(const MConstPtr&, FilterFailureReason)> FailureCallback;
00054 #ifdef RVIZ_USE_BOOST_SIGNAL_1
00055         typedef boost::signal<void(const MConstPtr&, FilterFailureReason)> FailureSignal;
00056 #else
00057         typedef boost::signals2::signal<void(const MConstPtr&, FilterFailureReason)> FailureSignal;
00058 #endif
00059 
00060         // If you hit this assert your message does not have a header, or does not have the HasHeader trait defined for it
00061         ROS_STATIC_ASSERT(ros::message_traits::HasHeader<M>::value);
00062 
00072         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))
00073             : MessageFilter<sensor_msgs::JointState>(tf, target_frame, queue_size, nh, max_rate)
00074             , tf_(tf)
00075             , nh_(nh)
00076             , max_rate_(max_rate)
00077             , queue_size_(queue_size)
00078             {
00079                 init();
00080 
00081                 setTargetFrame(target_frame);
00082             }
00083 
00094         template<class F>
00095         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))
00096             : tf_(tf)
00097             , nh_(nh)
00098             , max_rate_(max_rate)
00099             , queue_size_(queue_size)
00100             , MessageFilter<sensor_msgs::JointState>(f, tf, target_frame, queue_size, nh, max_rate)
00101             {
00102                 init();
00103 
00104                 setTargetFrame(target_frame);
00105 
00106                 connectInput(f);
00107             }
00108 
00112         template<class F>
00113         void connectInput(F& f)
00114             {
00115                 message_connection_.disconnect();
00116                 message_connection_ = f.registerCallback(&MessageFilterJointState::incomingMessage, this);
00117             }
00118 
00122         ~MessageFilterJointState()
00123             {
00124                 message_connection_.disconnect();
00125                 tf_.removeTransformsChangedListener(tf_connection_);
00126 
00127                 clear();
00128 
00129                 TF_MESSAGEFILTER_DEBUG("Successful Transforms: %llu, Failed Transforms: %llu, Discarded due to age: %llu, Transform messages received: %llu, Messages received: %llu, Total dropped: %llu",
00130                                        (long long unsigned int)successful_transform_count_, (long long unsigned int)failed_transform_count_,
00131                                        (long long unsigned int)failed_out_the_back_count_, (long long unsigned int)transform_message_count_,
00132                                        (long long unsigned int)incoming_message_count_, (long long unsigned int)dropped_message_count_);
00133 
00134             }
00135 
00139         void setTargetFrame(const std::string& target_frame)
00140             {
00141                 std::vector<std::string> frames;
00142                 frames.push_back(target_frame);
00143                 setTargetFrames(frames);
00144             }
00145 
00149         void setTargetFrames(const std::vector<std::string>& target_frames)
00150             {
00151                 boost::mutex::scoped_lock list_lock(messages_mutex_);
00152                 boost::mutex::scoped_lock string_lock(target_frames_string_mutex_);
00153 
00154                 target_frames_ = target_frames;
00155 
00156                 std::stringstream ss;
00157                 for (std::vector<std::string>::iterator it = target_frames_.begin(); it != target_frames_.end(); ++it)
00158                 {
00159                     *it = tf::resolve(tf_.getTFPrefix(), *it);
00160                     ss << *it << " ";
00161                 }
00162                 target_frames_string_ = ss.str();
00163             }
00167         std::string getTargetFramesString()
00168             {
00169                 boost::mutex::scoped_lock lock(target_frames_string_mutex_);
00170                 return target_frames_string_;
00171             };
00172 
00176         void setTolerance(const ros::Duration& tolerance)
00177             {
00178                 time_tolerance_ = tolerance;
00179             }
00180 
00184         void clear()
00185             {
00186                 boost::mutex::scoped_lock lock(messages_mutex_);
00187 
00188                 TF_MESSAGEFILTER_DEBUG("%s", "Cleared");
00189 
00190                 messages_.clear();
00191                 message_count_ = 0;
00192 
00193                 warned_about_unresolved_name_ = false;
00194                 warned_about_empty_frame_id_ = false;
00195             }
00196 
00197         void add(const MEvent& evt)
00198             {
00199                 boost::mutex::scoped_lock lock(messages_mutex_);
00200 
00201                 testMessages();
00202 
00203                 if (!testMessage(evt))
00204                 {
00205                     // If this message is about to push us past our queue size, erase the oldest message
00206                     if (queue_size_ != 0 && message_count_ + 1 > queue_size_)
00207                     {
00208                         ++dropped_message_count_;
00209                         const MEvent& front = messages_.front();
00210                         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());
00211                         signalFailure(messages_.front(), filter_failure_reasons::Unknown);
00212 
00213                         messages_.pop_front();
00214                         --message_count_;
00215                     }
00216 
00217                     // Add the message to our list
00218                     messages_.push_back(evt);
00219                     ++message_count_;
00220                 }
00221 
00222                 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_);
00223 
00224                 ++incoming_message_count_;
00225             }
00226 
00232         void add(const MConstPtr& message)
00233             {
00234                 boost::shared_ptr<std::map<std::string, std::string> > header(new std::map<std::string, std::string>);
00235                 (*header)["callerid"] = "unknown";
00236                 add(MEvent(message, header, ros::Time::now()));
00237             }
00238 
00243         message_filters::Connection registerFailureCallback(const FailureCallback& callback)
00244             {
00245                 boost::mutex::scoped_lock lock(failure_signal_mutex_);
00246                 return message_filters::Connection(boost::bind(&MessageFilterJointState::disconnectFailure, this, _1), failure_signal_.connect(callback));
00247             }
00248 
00249         virtual void setQueueSize( uint32_t new_queue_size )
00250             {
00251                 queue_size_ = new_queue_size;
00252             }
00253 
00254         virtual uint32_t getQueueSize()
00255             {
00256                 return queue_size_;
00257             }
00258 
00259     private:
00260 
00261         void init()
00262             {
00263                 message_count_ = 0;
00264                 new_transforms_ = false;
00265                 successful_transform_count_ = 0;
00266                 failed_transform_count_ = 0;
00267                 failed_out_the_back_count_ = 0;
00268                 transform_message_count_ = 0;
00269                 incoming_message_count_ = 0;
00270                 dropped_message_count_ = 0;
00271                 time_tolerance_ = ros::Duration(0.0);
00272                 warned_about_unresolved_name_ = false;
00273                 warned_about_empty_frame_id_ = false;
00274 
00275                 tf_connection_ = tf_.addTransformsChangedListener(boost::bind(&MessageFilterJointState::transformsChanged, this));
00276 
00277                 max_rate_timer_ = nh_.createTimer(max_rate_, &MessageFilterJointState::maxRateTimerCallback, this);
00278             }
00279 
00280         typedef std::list<MEvent> L_Event;
00281 
00282         bool testMessage(const MEvent& evt)
00283             {
00284                 const MConstPtr& message = evt.getMessage();
00285                 std::string callerid = evt.getPublisherName();
00286                 std::string frame_id = ros::message_traits::FrameId<M>::value(*message);
00287                 ros::Time stamp = ros::message_traits::TimeStamp<M>::value(*message);
00288 
00289                 // FIXED
00290                 if (frame_id.empty()) frame_id = * (target_frames_.begin());
00291                 //Throw out messages which have an empty frame_id
00292                 if (frame_id.empty())
00293                 {
00294                     if (!warned_about_empty_frame_id_)
00295                     {
00296                         warned_about_empty_frame_id_ = true;
00297                         TF_MESSAGEFILTER_WARN("Discarding message from [%s] due to empty frame_id.  This message will only print once.", callerid.c_str());
00298                     }
00299                     signalFailure(evt, filter_failure_reasons::EmptyFrameID);
00300                     return true;
00301                 }
00302 
00303                 if (frame_id[0] != '/')
00304                 {
00305                     std::string unresolved = frame_id;
00306                     frame_id = tf::resolve(tf_.getTFPrefix(), frame_id);
00307 
00308                     if (!warned_about_unresolved_name_)
00309                     {
00310                         warned_about_unresolved_name_ = true;
00311                         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());
00312                     }
00313                 }
00314 
00315                 //Throw out messages which are too old
00317                 for (std::vector<std::string>::iterator target_it = target_frames_.begin(); target_it != target_frames_.end(); ++target_it)
00318                 {
00319                     const std::string& target_frame = *target_it;
00320 
00321                     if (target_frame != frame_id && stamp != ros::Time(0))
00322                     {
00323                         ros::Time latest_transform_time ;
00324 
00325                         tf_.getLatestCommonTime(frame_id, target_frame, latest_transform_time, 0) ;
00326                         if (stamp + tf_.getCacheLength() < latest_transform_time)
00327                         {
00328                             ++failed_out_the_back_count_;
00329                             ++dropped_message_count_;
00330                             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_);
00331 
00332                             last_out_the_back_stamp_ = stamp;
00333                             last_out_the_back_frame_ = frame_id;
00334 
00335                             signalFailure(evt, filter_failure_reasons::OutTheBack);
00336                             return true;
00337                         }
00338                     }
00339 
00340                 }
00341 
00342                 bool ready = !target_frames_.empty();
00343                 for (std::vector<std::string>::iterator target_it = target_frames_.begin(); ready && target_it != target_frames_.end(); ++target_it)
00344                 {
00345                     std::string& target_frame = *target_it;
00346                     if (time_tolerance_ != ros::Duration(0.0))
00347                     {
00348                         ready = ready && (tf_.canTransform(target_frame, frame_id, stamp) &&
00349                                           tf_.canTransform(target_frame, frame_id, stamp + time_tolerance_) );
00350                     }
00351                     else
00352                     {
00353                         ready = ready && tf_.canTransform(target_frame, frame_id, stamp);
00354                     }
00355                 }
00356 
00357                 if (ready)
00358                 {
00359                     TF_MESSAGEFILTER_DEBUG("Message ready in frame %s at time %.3f, count now %d", frame_id.c_str(), stamp.toSec(), message_count_);
00360 
00361                     ++successful_transform_count_;
00362 
00363                     signalMessage(evt);
00364                 }
00365                 else
00366                 {
00367                     ++failed_transform_count_;
00368                 }
00369 
00370                 return ready;
00371             }
00372 
00373         void testMessages()
00374             {
00375                 if (!messages_.empty() && getTargetFramesString() == " ")
00376                 {
00377                     ROS_WARN_NAMED("message_notifier", "MessageFilter [target=%s]: empty target frame", getTargetFramesString().c_str());
00378                 }
00379 
00380                 int i = 0;
00381 
00382                 L_Event::iterator it = messages_.begin();
00383                 for (; it != messages_.end(); ++i)
00384                 {
00385                     MEvent& evt = *it;
00386 
00387                     if (testMessage(evt))
00388                     {
00389                         --message_count_;
00390                         it = messages_.erase(it);
00391                     }
00392                     else
00393                     {
00394                         ++it;
00395                     }
00396                 }
00397             }
00398 
00399         void maxRateTimerCallback(const ros::TimerEvent&)
00400             {
00401                 boost::mutex::scoped_lock list_lock(messages_mutex_);
00402                 if (new_transforms_)
00403                 {
00404                     testMessages();
00405                     new_transforms_ = false;
00406                 }
00407 
00408                 checkFailures();
00409             }
00410 
00414         void incomingMessage(const ros::MessageEvent<M const>& evt)
00415             {
00416                 add(evt);
00417             }
00418 
00419         void transformsChanged()
00420             {
00421                 new_transforms_ = true;
00422 
00423                 ++transform_message_count_;
00424             }
00425 
00426         void checkFailures()
00427             {
00428                 if (next_failure_warning_.isZero())
00429                 {
00430                     next_failure_warning_ = ros::Time::now() + ros::Duration(15);
00431                 }
00432 
00433                 if (ros::Time::now() >= next_failure_warning_)
00434                 {
00435                     if (incoming_message_count_ - message_count_ == 0)
00436                     {
00437                         return;
00438                     }
00439 
00440                     double dropped_pct = (double)dropped_message_count_ / (double)(incoming_message_count_ - message_count_);
00441                     if (dropped_pct > 0.95)
00442                     {
00443                         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);
00444                         next_failure_warning_ = ros::Time::now() + ros::Duration(60);
00445 
00446                         if ((double)failed_out_the_back_count_ / (double)dropped_message_count_ > 0.5)
00447                         {
00448                             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());
00449                         }
00450                     }
00451                 }
00452             }
00453 
00454         void disconnectFailure(const message_filters::Connection& c)
00455             {
00456                 boost::mutex::scoped_lock lock(failure_signal_mutex_);
00457                 c.getBoostConnection().disconnect();
00458             }
00459 
00460         void signalFailure(const MEvent& evt, FilterFailureReason reason)
00461             {
00462                 boost::mutex::scoped_lock lock(failure_signal_mutex_);
00463                 failure_signal_(evt.getMessage(), reason);
00464             }
00465 
00466         Transformer& tf_; 
00467         ros::NodeHandle nh_; 
00468         ros::Duration max_rate_;
00469         ros::Timer max_rate_timer_;
00470         std::vector<std::string> target_frames_; 
00471         std::string target_frames_string_;
00472         boost::mutex target_frames_string_mutex_;
00473         uint32_t queue_size_; 
00474 
00475         L_Event messages_; 
00476         uint32_t message_count_; 
00477         boost::mutex messages_mutex_; 
00478 
00479         bool new_messages_; 
00480         volatile bool new_transforms_; 
00481 
00482         bool warned_about_unresolved_name_;
00483         bool warned_about_empty_frame_id_;
00484 
00485         uint64_t successful_transform_count_;
00486         uint64_t failed_transform_count_;
00487         uint64_t failed_out_the_back_count_;
00488         uint64_t transform_message_count_;
00489         uint64_t incoming_message_count_;
00490         uint64_t dropped_message_count_;
00491 
00492         ros::Time last_out_the_back_stamp_;
00493         std::string last_out_the_back_frame_;
00494 
00495         ros::Time next_failure_warning_;
00496 
00497         ros::Duration time_tolerance_; 
00498 
00499 #ifdef RVIZ_USE_BOOST_SIGNAL_1
00500         boost::signals::connection tf_connection_;
00501 #else
00502         boost::signals2::connection tf_connection_;
00503 #endif
00504         message_filters::Connection message_connection_;
00505 
00506         FailureSignal failure_signal_;
00507         boost::mutex failure_signal_mutex_;
00508     };
00509 }
00510 
00511 #ifndef Q_MOC_RUN
00512 #include <message_filters/subscriber.h>
00513 #include <tf/message_filter.h>
00514 #endif
00515 
00516 #include "rviz/display_context.h"
00517 #include "rviz/frame_manager.h"
00518 #include "rviz/properties/ros_topic_property.h"
00519 
00520 namespace rviz
00521 {
00528 class MessageFilterJointStateDisplay: public _RosTopicDisplay
00529 {
00530 // No Q_OBJECT macro here, moc does not support Q_OBJECT in a templated class.
00531 public:
00534   typedef MessageFilterJointStateDisplay MFDClass;
00535 
00536   MessageFilterJointStateDisplay()
00537     : tf_filter_( NULL )
00538     , messages_received_( 0 )
00539     {
00540       QString message_type = QString::fromStdString( ros::message_traits::datatype<sensor_msgs::JointState>() );
00541       topic_property_->setMessageType( message_type );
00542       topic_property_->setDescription( message_type + " topic to subscribe to." );
00543     }
00544 
00545   virtual void onInitialize()
00546     {
00547       tf_filter_ = new tf::MessageFilterJointState( *context_->getTFClient(),
00548                                                     fixed_frame_.toStdString(), 10, update_nh_ );
00549 
00550       tf_filter_->connectInput( sub_ );
00551       tf_filter_->registerCallback( boost::bind( &MessageFilterJointStateDisplay::incomingMessage, this, _1 ));
00552       context_->getFrameManager()->registerFilterForTransformStatusCheck( tf_filter_, this );
00553     }
00554 
00555   virtual ~MessageFilterJointStateDisplay()
00556     {
00557       unsubscribe();
00558       delete tf_filter_;
00559     }
00560 
00561   virtual void reset()
00562     {
00563       Display::reset();
00564       tf_filter_->clear();
00565       messages_received_ = 0;
00566     }
00567 
00568 protected:
00569   virtual void updateTopic()
00570     {
00571       unsubscribe();
00572       reset();
00573       subscribe();
00574       context_->queueRender();
00575     }
00576 
00577   virtual void subscribe()
00578     {
00579       if( !isEnabled() )
00580       {
00581         return;
00582       }
00583 
00584       try
00585       {
00586         sub_.subscribe( update_nh_, topic_property_->getTopicStd(), 10 );
00587         setStatus( StatusProperty::Ok, "Topic", "OK" );
00588       }
00589       catch( ros::Exception& e )
00590       {
00591         setStatus( StatusProperty::Error, "Topic", QString( "Error subscribing: " ) + e.what() );
00592       }
00593     }
00594 
00595   virtual void unsubscribe()
00596     {
00597       sub_.unsubscribe();
00598     }
00599 
00600   virtual void onEnable()
00601     {
00602       subscribe();
00603     }
00604 
00605   virtual void onDisable()
00606     {
00607       unsubscribe();
00608       reset();
00609     }
00610 
00611   virtual void fixedFrameChanged()
00612     {
00613       tf_filter_->setTargetFrame( fixed_frame_.toStdString() );
00614       reset();
00615     }
00616 
00620   void incomingMessage( const sensor_msgs::JointState::ConstPtr& msg )
00621     {
00622       if( !msg )
00623       {
00624         return;
00625       }
00626 
00627       ++messages_received_;
00628       setStatus( StatusProperty::Ok, "Topic", QString::number( messages_received_ ) + " messages received" );
00629 
00630       processMessage( msg );
00631     }
00632 
00636   virtual void processMessage( const sensor_msgs::JointState::ConstPtr& msg ) = 0;
00637 
00638   message_filters::Subscriber<sensor_msgs::JointState> sub_;
00639   tf::MessageFilterJointState* tf_filter_;
00640   uint32_t messages_received_;
00641 };
00642 } // rviz
00643 
00644 namespace rviz
00645 {
00646     class JointInfo: public QObject {
00647         Q_OBJECT
00648         public:
00649         JointInfo(const std::string name, rviz::Property* parent_category);
00650         ~JointInfo();
00651 
00652         void setEffort(double e);
00653         double getEffort();
00654         void setMaxEffort(double m);
00655         double getMaxEffort();
00656         bool getEnabled() const;
00657 
00658         ros::Time last_update_;
00659 
00660     public Q_SLOTS:
00661         void updateVisibility();
00662 
00663     private:
00664         std::string name_;
00665         double effort_, max_effort_;
00666 
00667         rviz::Property* category_;
00668         rviz::FloatProperty* effort_property_;
00669         rviz::FloatProperty* max_effort_property_;
00670     };
00671 
00672     typedef std::set<JointInfo*> S_JointInfo;
00673     typedef std::vector<std::string> V_string;
00674 
00675     class EffortVisual;
00676 
00677     class EffortDisplay: public rviz::MessageFilterJointStateDisplay
00678     {
00679     Q_OBJECT
00680     public:
00681         // Constructor.  pluginlib::ClassLoader creates instances by calling
00682         // the default constructor, so make sure you have one.
00683         EffortDisplay();
00684         virtual ~EffortDisplay();
00685 
00686         // Overrides of public virtual functions from the Display class.
00687         virtual void onInitialize();
00688         virtual void reset();
00689 
00690     private Q_SLOTS:
00691         // Helper function to apply color and alpha to all visuals.
00692         void updateColorAndAlpha();
00693         void updateHistoryLength();
00694         void updateRobotDescription();
00695 
00696         JointInfo* getJointInfo( const std::string& joint);
00697         JointInfo* createJoint(const std::string &joint);
00698 
00699     protected:
00700         // overrides from Display
00701         virtual void onEnable();
00702         virtual void onDisable();
00703 
00704         // load
00705         void load();
00706         void clear();
00707 
00708         // The object for urdf model
00709         boost::shared_ptr<urdf::Model> robot_model_;
00710 
00711         //
00712         std::string robot_description_;
00713 
00714     private:
00715         void processMessage( const sensor_msgs::JointState::ConstPtr& msg );
00716 
00717         // Storage for the list of visuals.  It is a circular buffer where
00718         // data gets popped from the front (oldest) and pushed to the back (newest)
00719         boost::circular_buffer<boost::shared_ptr<EffortVisual> > visuals_;
00720 
00721         typedef std::map<std::string, JointInfo*> M_JointInfo;
00722         M_JointInfo joints_;
00723 
00724         // Property objects for user-editable properties.
00725         rviz::FloatProperty *alpha_property_,* width_property_,* scale_property_;
00726         rviz::IntProperty *history_length_property_;
00727 
00728         rviz::StringProperty *robot_description_property_;
00729         rviz::Property *joints_category_;
00730         rviz::BoolProperty *all_enabled_property_;
00731     };
00732 } // end namespace rviz_plugin_tutorials
00733 
00734 #endif // EFFORT_DISPLAY_H


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Tue Oct 3 2017 03:19:30