effort_visual.h
Go to the documentation of this file.
1 #ifndef EFFORT_VISUAL_H
2 #define EFFORT_VISUAL_H
3 
4 #include <sensor_msgs/JointState.h>
5 
6 namespace Ogre
7 {
8  class Vector3;
9  class Quaternion;
10 }
11 
12 namespace urdf
13 {
14  class Model;
15 }
16 
17 namespace rviz
18 {
19  class Arrow;
20  class BillboardLine;
21 }
22 
23 namespace rviz
24 {
25 
26 
27 // Each instance of EffortVisual represents the visualization of a single
28 // sensor_msgs::Effort message. Currently it just shows an arrow with
29 // the direction and magnitude of the acceleration vector, but could
30 // easily be expanded to include more of the message data.
32 {
33 public:
34  // Constructor. Creates the visual stuff and puts it into the
35  // scene, but in an unconfigured state.
36  EffortVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node, boost::shared_ptr<urdf::Model> urdf_model );
37 
38  // Destructor. Removes the visual stuff from the scene.
39  virtual ~EffortVisual();
40 
41  // set rainbow color
42  void getRainbowColor(float value, Ogre::ColourValue& color);
43  // Configure the visual to show the data in the message.
44  void setMessage( const sensor_msgs::JointStateConstPtr& msg );
45 
46  // Set the pose of the coordinate frame the message refers to.
47  // These could be done inside setMessage(), but that would require
48  // calls to FrameManager and error handling inside setMessage(),
49  // which doesn't seem as clean. This way EffortVisual is only
50  // responsible for visualization.
51  void setFramePosition( const Ogre::Vector3& position );
52  void setFrameOrientation( const Ogre::Quaternion& orientation );
53 
54  // set the pose of coordinates frame the each joint refers to.
55  void setFramePosition( const std::string joint_name, const Ogre::Vector3& position );
56  void setFrameOrientation( const std::string joint_name, const Ogre::Quaternion& orientation );
57 
58  void setFrameEnabled( const std::string joint_name, const bool e );
59 
60  // Set the color and alpha of the visual, which are user-editable
61  // parameters and therefore don't come from the Effort message.
62  void setColor( float r, float g, float b, float a );
63 
64  void setWidth( float w );
65 
66  void setScale( float s );
67 
68 private:
69  // The object implementing the effort circle
70  std::map<std::string, rviz::BillboardLine*> effort_circle_;
71  std::map<std::string, rviz::Arrow*> effort_arrow_;
72  std::map<std::string, bool> effort_enabled_;
73 
74  // A SceneNode whose pose is set to match the coordinate frame of
75  // the Effort message header.
76  Ogre::SceneNode* frame_node_;
77 
78  // The SceneManager, kept here only so the destructor can ask it to
79  // destroy the ``frame_node_``.
80  Ogre::SceneManager* scene_manager_;
81 
82  std::map<std::string, Ogre::Vector3> position_;
83  std::map<std::string, Ogre::Quaternion> orientation_;
84 
85  float width_, scale_;
86 
87  // The object for urdf model
89 };
90 
91 } // end namespace rviz
92 
93 #endif // EFFORT_VISUAL_H
std::map< std::string, Ogre::Quaternion > orientation_
Definition: effort_visual.h:83
XmlRpcServer s
std::map< std::string, rviz::Arrow * > effort_arrow_
Definition: effort_visual.h:71
Ogre::SceneNode * frame_node_
Definition: effort_visual.h:76
std::map< std::string, Ogre::Vector3 > position_
Definition: effort_visual.h:82
TFSIMD_FORCE_INLINE Vector3()
std::map< std::string, rviz::BillboardLine * > effort_circle_
Definition: effort_visual.h:70
Ogre::SceneManager * scene_manager_
Definition: effort_visual.h:80
std::map< std::string, bool > effort_enabled_
Definition: effort_visual.h:72
TFSIMD_FORCE_INLINE const tfScalar & w() const
boost::shared_ptr< urdf::Model > urdf_model_
Definition: effort_visual.h:88
r
static void getRainbowColor(float value, Ogre::ColourValue &color)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:51