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
00028
00029
00030
00031 class EffortVisual
00032 {
00033 public:
00034
00035
00036 EffortVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node, boost::shared_ptr<urdf::Model> urdf_model );
00037
00038
00039 virtual ~EffortVisual();
00040
00041
00042 void getRainbowColor(float value, Ogre::ColourValue& color);
00043
00044 void setMessage( const sensor_msgs::JointStateConstPtr& msg );
00045
00046
00047
00048
00049
00050
00051 void setFramePosition( const Ogre::Vector3& position );
00052 void setFrameOrientation( const Ogre::Quaternion& orientation );
00053
00054
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
00061
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
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
00075
00076 Ogre::SceneNode* frame_node_;
00077
00078
00079
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
00088 boost::shared_ptr<urdf::Model> urdf_model_;
00089 };
00090
00091 }
00092
00093 #endif // EFFORT_VISUAL_H