wrench_display.cpp
Go to the documentation of this file.
00001 #include <OGRE/OgreSceneNode.h>
00002 #include <OGRE/OgreSceneManager.h>
00003 
00004 #include <rviz/visualization_manager.h>
00005 #include <rviz/frame_manager.h>
00006 #include <rviz/properties/color_property.h>
00007 #include <rviz/properties/float_property.h>
00008 #include <rviz/properties/int_property.h>
00009 #include <rviz/properties/parse_color.h>
00010 #include <rviz/validate_floats.h>
00011 
00012 #include <boost/foreach.hpp>
00013 
00014 #include "wrench_visual.h"
00015 
00016 #include "wrench_display.h"
00017 
00018 namespace rviz
00019 {
00020 
00021     WrenchStampedDisplay::WrenchStampedDisplay()
00022     {
00023         force_color_property_ =
00024             new rviz::ColorProperty( "Force Color", QColor( 204, 51, 51 ),
00025                                      "Color to draw the force arrows.",
00026                                      this, SLOT( updateColorAndAlpha() ));
00027 
00028         torque_color_property_ =
00029             new rviz::ColorProperty( "Torque Color", QColor( 204, 204, 51),
00030                                      "Color to draw the torque arrows.",
00031                                      this, SLOT( updateColorAndAlpha() ));
00032 
00033         alpha_property_ =
00034             new rviz::FloatProperty( "Alpha", 1.0,
00035                                      "0 is fully transparent, 1.0 is fully opaque.",
00036                                      this, SLOT( updateColorAndAlpha() ));
00037 
00038         scale_property_ =
00039             new rviz::FloatProperty( "Arrow Scale", 2.0,
00040                                      "arrow scale",
00041                                      this, SLOT( updateColorAndAlpha() ));
00042 
00043         width_property_ =
00044             new rviz::FloatProperty( "Arrow Width", 0.5,
00045                                      "arrow width",
00046                                      this, SLOT( updateColorAndAlpha() ));
00047 
00048 
00049         history_length_property_ =
00050             new rviz::IntProperty( "History Length", 1,
00051                                    "Number of prior measurements to display.",
00052                                    this, SLOT( updateHistoryLength() ));
00053 
00054         history_length_property_->setMin( 1 );
00055         history_length_property_->setMax( 100000 );
00056     }
00057 
00058     void WrenchStampedDisplay::onInitialize()
00059     {
00060         MFDClass::onInitialize();
00061         updateHistoryLength( );
00062     }
00063 
00064     WrenchStampedDisplay::~WrenchStampedDisplay()
00065     {
00066     }
00067 
00068     // Override rviz::Display's reset() function to add a call to clear().
00069     void WrenchStampedDisplay::reset()
00070     {
00071         MFDClass::reset();
00072         visuals_.clear();
00073     }
00074 
00075     void WrenchStampedDisplay::updateColorAndAlpha()
00076     {
00077         float alpha = alpha_property_->getFloat();
00078         float scale = scale_property_->getFloat();
00079         float width = width_property_->getFloat();
00080         Ogre::ColourValue force_color = force_color_property_->getOgreColor();
00081         Ogre::ColourValue torque_color = torque_color_property_->getOgreColor();
00082 
00083         for( size_t i = 0; i < visuals_.size(); i++ )
00084         {
00085             visuals_[i]->setForceColor( force_color.r, force_color.g, force_color.b, alpha );
00086             visuals_[i]->setTorqueColor( torque_color.r, torque_color.g, torque_color.b, alpha );
00087             visuals_[i]->setScale( scale );
00088             visuals_[i]->setWidth( width );
00089         }
00090     }
00091 
00092     // Set the number of past visuals to show.
00093     void WrenchStampedDisplay::updateHistoryLength()
00094     {
00095         visuals_.rset_capacity(history_length_property_->getInt());
00096     }
00097 
00098     bool validateFloats( const geometry_msgs::WrenchStamped& msg )
00099     {
00100         return rviz::validateFloats(msg.wrench.force) && rviz::validateFloats(msg.wrench.torque) ;
00101     }
00102 
00103     // This is our callback to handle an incoming message.
00104     void WrenchStampedDisplay::processMessage( const geometry_msgs::WrenchStamped::ConstPtr& msg )
00105     {
00106         if( !validateFloats( *msg ))
00107             {
00108                 setStatus( rviz::StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)" );
00109                 return;
00110             }
00111 
00112         // Here we call the rviz::FrameManager to get the transform from the
00113         // fixed frame to the frame in the header of this Imu message.  If
00114         // it fails, we can't do anything else so we return.
00115         Ogre::Quaternion orientation;
00116         Ogre::Vector3 position;
00117         if( !context_->getFrameManager()->getTransform( msg->header.frame_id,
00118                                                         msg->header.stamp,
00119                                                         position, orientation ))
00120           {
00121             ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'",
00122                        msg->header.frame_id.c_str(), qPrintable( fixed_frame_ ));
00123             return;
00124           }
00125 
00126         // We are keeping a circular buffer of visual pointers.  This gets
00127         // the next one, or creates and stores it if the buffer is not full
00128         boost::shared_ptr<WrenchStampedVisual> visual;
00129         if( visuals_.full() )
00130             {
00131                 visual = visuals_.front();
00132             }
00133         else
00134             {
00135                 visual.reset(new WrenchStampedVisual( context_->getSceneManager(), scene_node_ ));
00136             }
00137 
00138         // Now set or update the contents of the chosen visual.
00139         visual->setMessage( msg );
00140         visual->setFramePosition( position );
00141         visual->setFrameOrientation( orientation );
00142         float alpha = alpha_property_->getFloat();
00143         float scale = scale_property_->getFloat();
00144         float width = width_property_->getFloat();
00145         Ogre::ColourValue force_color = force_color_property_->getOgreColor();
00146         Ogre::ColourValue torque_color = torque_color_property_->getOgreColor();
00147         visual->setForceColor( force_color.r, force_color.g, force_color.b, alpha );
00148         visual->setTorqueColor( torque_color.r, torque_color.g, torque_color.b, alpha );
00149         visual->setScale( scale );
00150         visual->setWidth( width );
00151 
00152         // And send it to the end of the circular buffer
00153         visuals_.push_back(visual);
00154     }
00155 
00156 } // end namespace rviz
00157 
00158 // Tell pluginlib about this class.  It is important to do this in
00159 // global scope, outside our package's namespace.
00160 #include <pluginlib/class_list_macros.h>
00161 PLUGINLIB_EXPORT_CLASS( rviz::WrenchStampedDisplay, rviz::Display )
00162 
00163 
00164 


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:36