wrench_display.h
Go to the documentation of this file.
00001 #ifndef WRENCHSTAMPED_DISPLAY_H
00002 #define WRENCHSTAMPED_DISPLAY_H
00003 
00004 #ifndef Q_MOC_RUN
00005 #include <boost/circular_buffer.hpp>
00006 #endif
00007 
00008 #include <geometry_msgs/WrenchStamped.h>
00009 #include <rviz/message_filter_display.h>
00010 
00011 namespace Ogre
00012 {
00013 class SceneNode;
00014 }
00015 
00016 namespace rviz
00017 {
00018 class ColorProperty;
00019 class ROSTopicStringProperty;
00020 class FloatProperty;
00021 class IntProperty;
00022 }
00023 
00024 namespace rviz
00025 {
00026 
00027 class WrenchStampedVisual;
00028 
00029 class WrenchStampedDisplay: public rviz::MessageFilterDisplay<geometry_msgs::WrenchStamped>
00030 {
00031     Q_OBJECT
00032 public:
00033     // Constructor.  pluginlib::ClassLoader creates instances by calling
00034     // the default constructor, so make sure you have one.
00035     WrenchStampedDisplay();
00036     virtual ~WrenchStampedDisplay();
00037 
00038 protected:
00039     // Overrides of public virtual functions from the Display class.
00040     virtual void onInitialize();
00041     virtual void reset();
00042 
00043 private Q_SLOTS:
00044     // Helper function to apply color and alpha to all visuals.
00045     void updateColorAndAlpha();
00046     void updateHistoryLength();
00047 
00048 private:
00049     // Function to handle an incoming ROS message.
00050     void processMessage( const geometry_msgs::WrenchStamped::ConstPtr& msg );
00051 
00052     // Storage for the list of visuals par each joint intem
00053     // Storage for the list of visuals.  It is a circular buffer where
00054     // data gets popped from the front (oldest) and pushed to the back (newest)
00055     boost::circular_buffer<boost::shared_ptr<WrenchStampedVisual> > visuals_;
00056 
00057     // Property objects for user-editable properties.
00058     rviz::ColorProperty *force_color_property_, *torque_color_property_;
00059     rviz::FloatProperty *alpha_property_, *force_scale_property_, *torque_scale_property_, *width_property_;
00060     rviz::IntProperty *history_length_property_;
00061 };
00062 } // end namespace rviz_plugin_tutorials
00063 
00064 #endif // WRENCHSTAMPED_DISPLAY_H


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Jun 6 2019 18:02:16