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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:36