ambient_sound_visual.h
Go to the documentation of this file.
1 #ifndef __AMBIENT_SOUND_VISUAL__
2 #define __AMBIENT_SOUND_VISUAL__
3 
4 #include <jsk_hark_msgs/HarkPower.h>
5 #include <OGRE/OgreVector3.h>
6 #include <OGRE/OgreQuaternion.h>
7 
8 namespace Ogre
9 {
10 class SceneManager;
11 class SceneNode;
12 //class Vector3;
13 //class Quaternion;
14 }
15 
16 namespace rviz
17 {
18 class BillboardLine;
19 //class Axes;
20 }
21 
22 namespace jsk_rviz_plugins
23 {
24 
25 // BEGIN_TUTORIAL
26 // Declare the visual class for this display.
27 //
28 // Each instance of AmbientSoundVisual represents the visualization of a single
29 // sensor_msgs::Imu message. Currently it just shows an arrow with
30 // the direction and magnitude of the acceleration vector, but could
31 // easily be expanded to include more of the message data.
33 {
34 public:
35  // Constructor. Creates the visual stuff and puts it into the
36  // scene, but in an unconfigured state.
37  AmbientSoundVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );
38 
39  // Destructor. Removes the visual stuff from the scene.
40  virtual ~AmbientSoundVisual();
41 
42  // Configure the visual to show the data in the message.
43  void setMessage( const jsk_hark_msgs::HarkPower::ConstPtr& msg );
44 
45  // Set the pose of the coordinate frame the message refers to.
46  // These could be done inside setMessage(), but that would require
47  // calls to FrameManager and error handling inside setMessage(),
48  // which doesn't seem as clean. This way AmbientSoundVisual is only
49  // responsible for visualization.
50  void setFramePosition( const Ogre::Vector3& position );
51  void setFrameOrientation( const Ogre::Quaternion& orientation );
52 
53  // Set the color and alpha of the visual, which are user-editable
54  // parameters and therefore don't come from the Imu message.
55  void setColor( float r, float g, float b, float a );
56 
57  void setWidth( float w );
58  void setScale( float s );
59  void setBias( float b );
60  void setGrad( float g );
61 
62 private:
63  // The object implementing the actual arrow shape
65  //rviz::Axes* axes_;
66 
67  // A SceneNode whose pose is set to match the coordinate frame of
68  // the Imu message header.
69  Ogre::SceneNode* frame_node_;
70 
71  // The SceneManager, kept here only so the destructor can ask it to
72  // destroy the ``frame_node_``.
73  Ogre::SceneManager* scene_manager_;
74 
75  Ogre::Vector3 position_;
76  Ogre::Quaternion orientation_;
77 
78  //std::map<std::string, Ogre::Vector3> position_;
79  //std::map<std::string, Ogre::Quaternion> orientation_;
81 };
82 // END_TUTORIAL
83 
84 } // end namespace jsk_rviz_plugins
85 
86 #endif // __AMBIENT_SOUND_VISUAL__
rviz::BillboardLine
jsk_rviz_plugins::AmbientSoundVisual::orientation_
Ogre::Quaternion orientation_
Definition: ambient_sound_visual.h:76
Ogre
msg
msg
jsk_rviz_plugins::AmbientSoundVisual::setBias
void setBias(float b)
Definition: ambient_sound_visual.cpp:114
jsk_rviz_plugins::AmbientSoundVisual::ambient_sound_power_line_
rviz::BillboardLine * ambient_sound_power_line_
Definition: ambient_sound_visual.h:64
jsk_rviz_plugins::AmbientSoundVisual::scene_manager_
Ogre::SceneManager * scene_manager_
Definition: ambient_sound_visual.h:73
bounding_box_sample.w
w
Definition: bounding_box_sample.py:29
jsk_rviz_plugins::AmbientSoundVisual::setColor
void setColor(float r, float g, float b, float a)
Definition: ambient_sound_visual.cpp:100
jsk_rviz_plugins::AmbientSoundVisual::grad_
float grad_
Definition: ambient_sound_visual.h:80
jsk_rviz_plugins::AmbientSoundVisual::bias_
float bias_
Definition: ambient_sound_visual.h:80
jsk_rviz_plugins::AmbientSoundVisual::AmbientSoundVisual
AmbientSoundVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node)
Definition: ambient_sound_visual.cpp:14
jsk_rviz_plugins::AmbientSoundVisual::position_
Ogre::Vector3 position_
Definition: ambient_sound_visual.h:75
overlay_menu_sample.b
b
Definition: overlay_menu_sample.py:20
jsk_rviz_plugins::AmbientSoundVisual::setMessage
void setMessage(const jsk_hark_msgs::HarkPower::ConstPtr &msg)
Definition: ambient_sound_visual.cpp:47
jsk_rviz_plugins::AmbientSoundVisual::width_
float width_
Definition: ambient_sound_visual.h:80
rviz
jsk_rviz_plugins::AmbientSoundVisual::setGrad
void setGrad(float g)
Definition: ambient_sound_visual.cpp:118
bounding_box_sample.r
r
Definition: bounding_box_sample.py:10
jsk_rviz_plugins::AmbientSoundVisual
Definition: ambient_sound_visual.h:32
jsk_rviz_plugins::AmbientSoundVisual::setWidth
void setWidth(float w)
Definition: ambient_sound_visual.cpp:106
jsk_rviz_plugins::AmbientSoundVisual::setFramePosition
void setFramePosition(const Ogre::Vector3 &position)
Definition: ambient_sound_visual.cpp:83
overlay_menu_sample.g
g
Definition: overlay_menu_sample.py:19
jsk_rviz_plugins::AmbientSoundVisual::frame_node_
Ogre::SceneNode * frame_node_
Definition: ambient_sound_visual.h:69
jsk_rviz_plugins::AmbientSoundVisual::~AmbientSoundVisual
virtual ~AmbientSoundVisual()
Definition: ambient_sound_visual.cpp:37
jsk_rviz_plugins::AmbientSoundVisual::setScale
void setScale(float s)
Definition: ambient_sound_visual.cpp:110
motor_states_temperature_decomposer.s
s
Definition: motor_states_temperature_decomposer.py:79
jsk_rviz_plugins
Definition: __init__.py:1
jsk_rviz_plugins::AmbientSoundVisual::setFrameOrientation
void setFrameOrientation(const Ogre::Quaternion &orientation)
Definition: ambient_sound_visual.cpp:90
jsk_rviz_plugins::AmbientSoundVisual::scale_
float scale_
Definition: ambient_sound_visual.h:80


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Mon Jan 22 2024 03:47:13