wrench_visual.h
Go to the documentation of this file.
1 #ifndef WRENCHSTAMPED_VISUAL_H
2 #define WRENCHSTAMPED_VISUAL_H
3 
4 #include <geometry_msgs/Wrench.h>
5 
6 namespace Ogre
7 {
8  class Vector3;
9  class Quaternion;
10 }
11 
12 namespace rviz
13 {
14  class Arrow;
15  class BillboardLine;
16 }
17 
18 namespace rviz
19 {
20 
21 
22 // Each instance of WrenchStampedVisual represents the visualization of a single
23 // sensor_msgs::WrenchStamped message. Currently it just shows an arrow with
24 // the direction and magnitude of the acceleration vector, but could
25 // easily be expanded to include more of the message data.
27 {
28 public:
29  // Constructor. Creates the visual stuff and puts it into the
30  // scene, but in an unconfigured state.
31  WrenchVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );
32 
33  // Destructor. Removes the visual stuff from the scene.
34  virtual ~WrenchVisual();
35 
36  // Configure the visual to show the given force and torque vectors
37  void setWrench( const Ogre::Vector3 &force, const Ogre::Vector3 &torque );
38  // Configure the visual to show the data in the message.
39  void setWrench( const geometry_msgs::Wrench& wrench );
40 
41  // Set the pose of the coordinate frame the message refers to.
42  // These could be done inside setMessage(), but that would require
43  // calls to FrameManager and error handling inside setMessage(),
44  // which doesn't seem as clean. This way WrenchStampedVisual is only
45  // responsible for visualization.
46  void setFramePosition( const Ogre::Vector3& position );
47  void setFrameOrientation( const Ogre::Quaternion& orientation );
48 
49  // Set the color and alpha of the visual, which are user-editable
50  // parameters and therefore don't come from the WrenchStamped message.
51  void setForceColor( float r, float g, float b, float a );
52  void setTorqueColor( float r, float g, float b, float a );
53  void setForceScale( float s );
54  void setTorqueScale( float s );
55  void setWidth( float w );
56  void setVisible( bool visible );
57 
58 private:
59  // The object implementing the wrenchStamped circle
64  float force_scale_, torque_scale_, width_;
65 
66  // A SceneNode whose pose is set to match the coordinate frame of
67  // the WrenchStamped message header.
68  Ogre::SceneNode* frame_node_;
69  // allow showing/hiding of force / torque arrows
70  Ogre::SceneNode* force_node_;
71  Ogre::SceneNode* torque_node_;
72 
73  // The SceneManager, kept here only so the destructor can ask it to
74  // destroy the ``frame_node_``.
75  Ogre::SceneManager* scene_manager_;
76 
77 };
78 
79 } // end namespace rviz
80 
81 #endif // WRENCHSTAMPED_VISUAL_H
rviz::BillboardLine * circle_torque_
Definition: wrench_visual.h:62
rviz::Arrow * circle_arrow_torque_
Definition: wrench_visual.h:63
Ogre::SceneManager * scene_manager_
Definition: wrench_visual.h:75
Ogre::SceneNode * frame_node_
Definition: wrench_visual.h:68
An object that displays a multi-segment line strip rendered as billboards.
XmlRpcServer s
Ogre::SceneNode * force_node_
Definition: wrench_visual.h:70
Ogre::SceneNode * torque_node_
Definition: wrench_visual.h:71
TFSIMD_FORCE_INLINE Vector3()
TFSIMD_FORCE_INLINE const tfScalar & w() const
rviz::Arrow * arrow_torque_
Definition: wrench_visual.h:61
rviz::Arrow * arrow_force_
Definition: wrench_visual.h:60
An arrow consisting of a cylinder and a cone.
Definition: arrow.h:59
r


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat Apr 27 2019 02:33:42