1 #include <OgreSceneNode.h> 2 #include <OgreSceneManager.h> 12 #include <boost/foreach.hpp> 25 "Color to draw the force arrows.",
30 "Color to draw the torque arrows.",
35 "0 is fully transparent, 1.0 is fully opaque.",
56 "Number of prior measurements to display.",
89 for(
size_t i = 0; i <
visuals_.size(); i++ )
91 visuals_[i]->setForceColor( force_color.r, force_color.g, force_color.b, alpha );
92 visuals_[i]->setTorqueColor( torque_color.r, torque_color.g, torque_color.b, alpha );
93 visuals_[i]->setForceScale( force_scale );
94 visuals_[i]->setTorqueScale( torque_scale );
122 Ogre::Quaternion orientation;
123 Ogre::Vector3 position;
126 position, orientation ))
128 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'",
129 msg->header.frame_id.c_str(), qPrintable(
fixed_frame_ ));
133 if ( position.isNaN() )
135 ROS_ERROR_THROTTLE(1.0,
"Wrench position contains NaNs. Skipping render as long as the position is invalid");
152 visual->setWrench( msg->wrench );
153 visual->setFramePosition( position );
154 visual->setFrameOrientation( orientation );
161 visual->setForceColor( force_color.r, force_color.g, force_color.b, alpha );
162 visual->setTorqueColor( torque_color.r, torque_color.g, torque_color.b, alpha );
163 visual->setForceScale( force_scale );
164 visual->setTorqueScale( torque_scale );
165 visual->setWidth( width );
rviz::FloatProperty * force_scale_property_
Ogre::ColourValue getOgreColor() const
virtual void onInitialize()
Override this function to do subclass-specific initialization.
boost::circular_buffer< boost::shared_ptr< WrenchVisual > > visuals_
rviz::ColorProperty * force_color_property_
virtual void onInitialize()
void updateColorAndAlpha()
virtual void reset()
Called to tell the display to clear its state.
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
rviz::FloatProperty * alpha_property_
virtual int getInt() const
Return the internal property value as an integer.
rviz::IntProperty * history_length_property_
virtual float getFloat() const
rviz::FloatProperty * torque_scale_property_
Property specialized to enforce floating point max/min.
Property specialized to provide max/min enforcement for integers.
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
bool validateFloats(const sensor_msgs::CameraInfo &msg)
#define ROS_ERROR_THROTTLE(period,...)
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
rviz::FloatProperty * width_property_
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
void processMessage(const geometry_msgs::WrenchStamped::ConstPtr &msg)
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Return the pose for a header, relative to the fixed frame, in Ogre classes.
rviz::ColorProperty * torque_color_property_
virtual ~WrenchStampedDisplay()
void updateHistoryLength()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.