Go to the documentation of this file.
   39 #include <OgreSceneManager.h> 
   40 #include <OgreSceneNode.h> 
   51                                                    "Distance, in meters from the last arrow dropped, " 
   52                                                    "that will cause a new arrow to drop.",
 
   57                                                 "Angular distance from the last arrow dropped, " 
   58                                                 "that will cause a new arrow to drop.",
 
   64                       "Number of arrows to keep before removing the oldest.  0 means keep all of them.",
 
   82       new FloatProperty(
"Shaft Length", 1, 
"Length of the each arrow's shaft, in meters.",
 
   87       new FloatProperty(
"Shaft Radius", 0.05, 
"Radius of the each arrow's shaft, in meters.",
 
   91       new FloatProperty(
"Head Length", 0.3, 
"Length of the each arrow's head, in meters.",
 
   96       new FloatProperty(
"Head Radius", 0.1, 
"Radius of the each arrow's head, in meters.",
 
  107                              "Whether or not the covariances of the messages should be shown.", 
this,
 
  133   D_Arrow::iterator it = 
arrows_.begin();
 
  134   D_Arrow::iterator end = 
arrows_.end();
 
  135   for (; it != end; ++it)
 
  144   D_Axes::iterator it_axes = 
axes_.begin();
 
  145   D_Axes::iterator end_axes = 
axes_.end();
 
  146   for (; it_axes != end_axes; ++it_axes)
 
  161   float red = color.redF();
 
  162   float green = color.greenF();
 
  163   float blue = color.blueF();
 
  166   D_Arrow::iterator it = 
arrows_.begin();
 
  167   D_Arrow::iterator end = 
arrows_.end();
 
  168   for (; it != end; ++it)
 
  171     arrow->
setColor(red, green, blue, alpha);
 
  178   D_Arrow::iterator it = 
arrows_.begin();
 
  179   D_Arrow::iterator end = 
arrows_.end();
 
  180   for (; it != end; ++it)
 
  189   D_Axes::iterator it = 
axes_.begin();
 
  190   D_Axes::iterator end = 
axes_.end();
 
  191   for (; it != end; ++it)
 
  232   D_Arrow::iterator it = 
arrows_.begin();
 
  233   D_Arrow::iterator end = 
arrows_.end();
 
  234   for (; it != end; ++it)
 
  236     (*it)->getSceneNode()->setVisible(use_arrow);
 
  239   D_Axes::iterator it_axes = 
axes_.begin();
 
  240   D_Axes::iterator end_axes = 
axes_.end();
 
  241   for (; it_axes != end_axes; ++it_axes)
 
  243     (*it_axes)->getSceneNode()->setVisible(!use_arrow);
 
  264               "Message contained invalid floating point values (nans or infs)");
 
  271                         "Odometry '%s' contains unnormalized quaternions. " 
  272                         "This warning will only be output once but may be true for others; " 
  273                         "enable DEBUG messages for ros.rviz.quaternions to see more details.",
 
  275     ROS_DEBUG_NAMED(
"quaternions", 
"Odometry '%s' contains unnormalized quaternions.",
 
  284     Ogre::Vector3 current_position(message->pose.pose.position.x, message->pose.pose.position.y,
 
  285                                    message->pose.pose.position.z);
 
  290     Eigen::Quaternionf current_orientation(message->pose.pose.orientation.w,
 
  291                                            message->pose.pose.orientation.x,
 
  292                                            message->pose.pose.orientation.y,
 
  293                                            message->pose.pose.orientation.z);
 
  302   Ogre::Vector3 position;
 
  303   Ogre::Quaternion orientation;
 
  306     ROS_ERROR(
"Error transforming odometry '%s' from frame '%s' to frame '%s'", qPrintable(
getName()),
 
  307               message->header.frame_id.c_str(), qPrintable(
fixed_frame_));
 
  328   arrow->
setOrientation(orientation * Ogre::Quaternion(Ogre::Degree(-90), Ogre::Vector3::UNIT_Y));
 
  331   cov->setPosition(position);
 
  332   cov->setOrientation(orientation);
 
  337   arrow->
setColor(color.redF(), color.greenF(), color.blueF(), alpha);
 
  340   cov->setCovariance(message->pose);
 
  348   axes_.push_back(axes);
 
  368       delete axes_.front();
 
  
void set(float shaft_length, float shaft_diameter, float head_length, float head_diameter)
Set the parameters for this arrow.
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this object.
rviz::FloatProperty * shaft_radius_property_
nav_msgs::Odometry::ConstPtr last_used_message_
virtual QColor getColor() const
Accumulates and displays the pose from a nav_msgs::Odometry message.
virtual void setHidden(bool hidden)
Hide or show this property in any PropertyTreeWidget viewing its parent.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
~OdometryDisplay() override
void queueRender()
Convenience function which calls context_->queueRender().
An arrow consisting of a cylinder and a cone.
bool initialized() const
Returns true if the display has been initialized.
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation.
void onInitialize() override
Override this function to do subclass-specific initialization.
CovarianceVisualPtr createAndPushBackVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node)
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
Property specialized to provide getter for booleans.
bool validateFloats(const sensor_msgs::CameraInfo &msg)
void updateColorAndAlpha()
void updateShapeVisibility()
#define ROS_WARN_ONCE_NAMED(name,...)
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
rviz::FloatProperty * head_length_property_
void onEnable() override
Overridden from MessageFilterDisplay to get Arrow/Axes visibility correct.
Property specialized to enforce floating point max/min.
rviz::EnumProperty * shape_property_
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual float getFloat() const
virtual void addOption(const QString &option, int value=0)
rviz::FloatProperty * axes_radius_property_
#define ROS_DEBUG_NAMED(name,...)
rviz::FloatProperty * shaft_length_property_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
void processMessage(const nav_msgs::Odometry::ConstPtr &message) override
rviz::FloatProperty * angle_tolerance_property_
bool validateQuaternions(const visualization_msgs::InteractiveMarker &marker)
rviz::FloatProperty * position_tolerance_property_
void updateGeometry(rviz::Arrow *arrow)
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
void reset() override
Called to tell the display to clear its state.
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
void onInitialize() override
virtual QString getName() const
Return the name of this Property as a QString.
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
CovarianceProperty * covariance_property_
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
rviz::FloatProperty * head_radius_property_
void updateArrowsGeometry()
bool transform(const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Transform a pose from a frame into the fixed frame.
rviz::FloatProperty * axes_length_property_
void set(float length, float radius, float alpha=1.0f)
Set the parameters on this object.
virtual int getInt() const
Return the internal property value as an integer.
void setPosition(const Ogre::Vector3 &position) override
Set the position of this object.
void updateAxisGeometry()
void setPosition(const Ogre::Vector3 &position) override
Set the position of the base of the arrow.
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation of the object.
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this arrow.
rviz::IntProperty * keep_property_
void setColor(float r, float g, float b, float a) override
Set the color of this arrow. Sets both the head and shaft color to the same value....
rviz::ColorProperty * color_property_
rviz::FloatProperty * alpha_property_
Property specialized to provide max/min enforcement for integers.
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall 
autogenerated on Sun May 4 2025 02:31:26