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


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Mon Oct 6 2014 01:18:44