00001 #ifndef __AMBIENT_SOUND_VISUAL__ 00002 #define __AMBIENT_SOUND_VISUAL__ 00003 00004 #include <hark_msgs/HarkPower.h> 00005 00006 namespace Ogre 00007 { 00008 class Vector3; 00009 class Quaternion; 00010 } 00011 00012 namespace rviz 00013 { 00014 class BillboardLine; 00015 //class Axes; 00016 } 00017 00018 namespace jsk_rviz_plugin 00019 { 00020 00021 // BEGIN_TUTORIAL 00022 // Declare the visual class for this display. 00023 // 00024 // Each instance of AmbientSoundVisual represents the visualization of a single 00025 // sensor_msgs::Imu message. Currently it just shows an arrow with 00026 // the direction and magnitude of the acceleration vector, but could 00027 // easily be expanded to include more of the message data. 00028 class AmbientSoundVisual 00029 { 00030 public: 00031 // Constructor. Creates the visual stuff and puts it into the 00032 // scene, but in an unconfigured state. 00033 AmbientSoundVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node ); 00034 00035 // Destructor. Removes the visual stuff from the scene. 00036 virtual ~AmbientSoundVisual(); 00037 00038 // Configure the visual to show the data in the message. 00039 void setMessage( const hark_msgs::HarkPower::ConstPtr& msg ); 00040 00041 // Set the pose of the coordinate frame the message refers to. 00042 // These could be done inside setMessage(), but that would require 00043 // calls to FrameManager and error handling inside setMessage(), 00044 // which doesn't seem as clean. This way AmbientSoundVisual is only 00045 // responsible for visualization. 00046 void setFramePosition( const Ogre::Vector3& position ); 00047 void setFrameOrientation( const Ogre::Quaternion& orientation ); 00048 00049 // Set the color and alpha of the visual, which are user-editable 00050 // parameters and therefore don't come from the Imu message. 00051 void setColor( float r, float g, float b, float a ); 00052 00053 void setWidth( float w ); 00054 void setScale( float s ); 00055 void setBias( float b ); 00056 void setGrad( float g ); 00057 00058 private: 00059 // The object implementing the actual arrow shape 00060 rviz::BillboardLine* ambient_sound_power_line_; 00061 //rviz::Axes* axes_; 00062 00063 // A SceneNode whose pose is set to match the coordinate frame of 00064 // the Imu message header. 00065 Ogre::SceneNode* frame_node_; 00066 00067 // The SceneManager, kept here only so the destructor can ask it to 00068 // destroy the ``frame_node_``. 00069 Ogre::SceneManager* scene_manager_; 00070 00071 Ogre::Vector3 position_; 00072 Ogre::Quaternion orientation_; 00073 float width_,scale_,bias_,grad_; 00074 }; 00075 // END_TUTORIAL 00076 00077 } // end namespace jsk_rviz_plugin 00078 00079 #endif // __AMBIENT_SOUND_VISUAL__