wrench_visual.h
Go to the documentation of this file.
00001 #ifndef WRENCHSTAMPED_VISUAL_H
00002 #define WRENCHSTAMPED_VISUAL_H
00003 
00004 #include <geometry_msgs/WrenchStamped.h>
00005 
00006 #ifdef __GNUC__
00007 #define RVIZ_DEPRECATED __attribute__ ((deprecated))
00008 #elif defined(_MSC_VER)
00009 #define RVIZ_DEPRECATED __declspec(deprecated)
00010 #else
00011 #pragma message("WARNING: You need to implement DEPRECATED for this compiler")
00012 #define RVIZ_DEPRECATED
00013 #endif
00014 
00015 namespace Ogre
00016 {
00017     class Vector3;
00018     class Quaternion;
00019 }
00020 
00021 namespace rviz
00022 {
00023     class Arrow;
00024     class BillboardLine;
00025 }
00026 
00027 namespace rviz
00028 {
00029 
00030 
00031 // Each instance of WrenchStampedVisual represents the visualization of a single
00032 // sensor_msgs::WrenchStamped message.  Currently it just shows an arrow with
00033 // the direction and magnitude of the acceleration vector, but could
00034 // easily be expanded to include more of the message data.
00035 class WrenchStampedVisual
00036 {
00037 public:
00038     // Constructor.  Creates the visual stuff and puts it into the
00039     // scene, but in an unconfigured state.
00040     WrenchStampedVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );
00041 
00042     // Destructor.  Removes the visual stuff from the scene.
00043     virtual ~WrenchStampedVisual();
00044 
00045     // Configure the visual to show the given force and torque vectors
00046     void setWrench( const Ogre::Vector3 &force, const Ogre::Vector3 &torque );
00047     // Configure the visual to show the data in the message.
00048     RVIZ_DEPRECATED
00049     void setMessage( const geometry_msgs::WrenchStamped::ConstPtr& msg );
00050     // Configure the visual to show the given wrench
00051     void setWrench( const geometry_msgs::Wrench& wrench );
00052 
00053     // Set the pose of the coordinate frame the message refers to.
00054     // These could be done inside setMessage(), but that would require
00055     // calls to FrameManager and error handling inside setMessage(),
00056     // which doesn't seem as clean.  This way WrenchStampedVisual is only
00057     // responsible for visualization.
00058     void setFramePosition( const Ogre::Vector3& position );
00059     void setFrameOrientation( const Ogre::Quaternion& orientation );
00060 
00061     // Set the color and alpha of the visual, which are user-editable
00062     // parameters and therefore don't come from the WrenchStamped message.
00063     void setForceColor( float r, float g, float b, float a );
00064     void setTorqueColor( float r, float g, float b, float a );
00065     void setForceScale( float s );
00066     void setTorqueScale( float s );
00067     void setWidth( float w );
00068     void setVisible( bool visible );
00069 
00070 private:
00071     // The object implementing the wrenchStamped circle
00072     rviz::Arrow* arrow_force_;
00073     rviz::Arrow* arrow_torque_;
00074     rviz::BillboardLine* circle_torque_;
00075     rviz::Arrow* circle_arrow_torque_;
00076     float force_scale_, torque_scale_, width_;
00077 
00078     // A SceneNode whose pose is set to match the coordinate frame of
00079     // the WrenchStamped message header.
00080     Ogre::SceneNode* frame_node_;
00081 
00082     // The SceneManager, kept here only so the destructor can ask it to
00083     // destroy the ``frame_node_``.
00084     Ogre::SceneManager* scene_manager_;
00085 
00086     // allow showing/hiding of force / torque arrows
00087     Ogre::SceneNode* force_node_;
00088     Ogre::SceneNode* torque_node_;
00089 };
00090 
00091 } // end namespace rviz
00092 
00093 #endif // WRENCHSTAMPED_VISUAL_H


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Jun 6 2019 18:02:16