effort_visual.h
Go to the documentation of this file.
00001 #ifndef EFFORT_VISUAL_H
00002 #define EFFORT_VISUAL_H
00003 
00004 #include <sensor_msgs/JointState.h>
00005 
00006 namespace Ogre
00007 {
00008     class Vector3;
00009     class Quaternion;
00010 }
00011 
00012 namespace urdf
00013 {
00014     class Model;
00015 }
00016 
00017 namespace rviz
00018 {
00019     class Arrow;
00020     class BillboardLine;
00021 }
00022 
00023 namespace rviz
00024 {
00025 
00026 
00027 // Each instance of EffortVisual represents the visualization of a single
00028 // sensor_msgs::Effort message.  Currently it just shows an arrow with
00029 // the direction and magnitude of the acceleration vector, but could
00030 // easily be expanded to include more of the message data.
00031 class EffortVisual
00032 {
00033 public:
00034     // Constructor.  Creates the visual stuff and puts it into the
00035     // scene, but in an unconfigured state.
00036     EffortVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node, boost::shared_ptr<urdf::Model> urdf_model );
00037 
00038     // Destructor.  Removes the visual stuff from the scene.
00039     virtual ~EffortVisual();
00040 
00041     // set rainbow color
00042     void getRainbowColor(float value, Ogre::ColourValue& color);
00043     // Configure the visual to show the data in the message.
00044     void setMessage( const sensor_msgs::JointStateConstPtr& msg );
00045 
00046     // Set the pose of the coordinate frame the message refers to.
00047     // These could be done inside setMessage(), but that would require
00048     // calls to FrameManager and error handling inside setMessage(),
00049     // which doesn't seem as clean.  This way EffortVisual is only
00050     // responsible for visualization.
00051     void setFramePosition( const Ogre::Vector3& position );
00052     void setFrameOrientation( const Ogre::Quaternion& orientation );
00053 
00054     // set the pose of coordinates frame the each joint refers to.
00055     void setFramePosition( const std::string joint_name, const Ogre::Vector3& position );
00056     void setFrameOrientation( const std::string joint_name, const Ogre::Quaternion& orientation );
00057 
00058     void setFrameEnabled( const std::string joint_name, const bool e );
00059 
00060     // Set the color and alpha of the visual, which are user-editable
00061     // parameters and therefore don't come from the Effort message.
00062     void setColor( float r, float g, float b, float a );
00063 
00064     void setWidth( float w );
00065 
00066     void setScale( float s );
00067 
00068 private:
00069     // The object implementing the effort circle
00070     std::map<std::string, rviz::BillboardLine*> effort_circle_;
00071     std::map<std::string, rviz::Arrow*> effort_arrow_;
00072     std::map<std::string, bool> effort_enabled_;
00073 
00074     // A SceneNode whose pose is set to match the coordinate frame of
00075     // the Effort message header.
00076     Ogre::SceneNode* frame_node_;
00077 
00078     // The SceneManager, kept here only so the destructor can ask it to
00079     // destroy the ``frame_node_``.
00080     Ogre::SceneManager* scene_manager_;
00081 
00082     std::map<std::string, Ogre::Vector3> position_;
00083     std::map<std::string, Ogre::Quaternion> orientation_;
00084 
00085     float width_, scale_;
00086 
00087     // The object for urdf model
00088     boost::shared_ptr<urdf::Model> urdf_model_;
00089 };
00090 
00091 } // end namespace rviz
00092 
00093 #endif // EFFORT_VISUAL_H


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