Go to the documentation of this file.
30 #include <boost/bind/bind.hpp>
32 #include <OgreSceneNode.h>
33 #include <OgreSceneManager.h>
34 #include <OgreManualObject.h>
35 #include <OgreMatrix4.h>
55 new EnumProperty(
"Line Style",
"Lines",
"The rendering operation to use to draw the grid lines.",
63 "The width, in meters, of each path line. Only works with the 'Billboards' style.",
this,
71 new FloatProperty(
"Alpha", 1.0,
"Amount of transparency to apply to the path.",
this);
78 "Offset", Ogre::Vector3::ZERO,
79 "Allows you to offset the path from the origin of the reference frame. In meters.",
this,
94 new ColorProperty(
"Pose Color", QColor(255, 85, 255),
"Color to draw the poses.",
this,
136 if (num > axes_vect.size())
138 for (
size_t i = axes_vect.size(); i < num; ++i)
143 axes_vect.push_back(axes);
146 else if (num < axes_vect.size())
148 for (
size_t i = num; i < axes_vect.size(); ++i)
152 axes_vect.resize(num);
158 if (num > arrow_vect.size())
160 for (
size_t i = arrow_vect.size(); i < num; ++i)
163 arrow_vect.push_back(arrow);
166 else if (num < arrow_vect.size())
168 for (
size_t i = num; i < arrow_vect.size(); ++i)
170 delete arrow_vect[i];
172 arrow_vect.resize(num);
275 std::vector<rviz::Axes*>& axes_vect =
axes_chain_[i];
276 for (
size_t j = 0; j < axes_vect.size(); j++)
290 std::vector<rviz::Arrow*>& arrow_vect =
arrow_chain_[i];
291 for (
size_t j = 0; j < arrow_vect.size(); j++)
293 arrow_vect[j]->setColor(color.redF(), color.greenF(), color.blueF(), 1.0f);
303 std::vector<rviz::Arrow*>& arrow_vect =
arrow_chain_[i];
304 for (
size_t j = 0; j < arrow_vect.size(); j++)
323 manual_object->clear();
325 manual_object =
nullptr;
335 delete billboard_line;
336 billboard_line =
nullptr;
361 Ogre::ManualObject* manual_object =
scene_manager_->createManualObject();
362 manual_object->setDynamic(
true);
395 Ogre::ManualObject* manual_object =
nullptr;
403 manual_object->clear();
408 billboard_line->
clear();
416 "Message contained invalid floating point values (nans or infs)");
423 "Path '%s' contains unnormalized quaternions. "
424 "This warning will only be output once but may be true for others; "
425 "enable DEBUG messages for ros.rviz.quaternions to see more details.",
431 Ogre::Vector3 position;
432 Ogre::Quaternion orientation;
435 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(),
439 Ogre::Matrix4 transform(orientation);
440 transform.setTrans(position);
448 uint32_t num_points = msg->poses.size();
454 manual_object->estimateVertexCount(num_points);
455 manual_object->begin(
"BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_STRIP,
456 Ogre::ResourceGroupManager::INTERNAL_RESOURCE_GROUP_NAME);
457 for (uint32_t i = 0; i < num_points; ++i)
459 const geometry_msgs::Point& pos = msg->poses[i].pose.position;
460 Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
461 manual_object->position(xpos.x, xpos.y, xpos.z);
462 manual_object->colour(color);
465 manual_object->end();
473 for (uint32_t i = 0; i < num_points; ++i)
475 const geometry_msgs::Point& pos = msg->poses[i].pose.position;
476 Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
477 billboard_line->
addPoint(xpos, color);
485 std::vector<rviz::Arrow*>& arrow_vect =
arrow_chain_[bufferIndex];
486 std::vector<rviz::Axes*>& axes_vect =
axes_chain_[bufferIndex];
492 for (uint32_t i = 0; i < num_points; ++i)
494 const geometry_msgs::Point& pos = msg->poses[i].pose.position;
495 const geometry_msgs::Quaternion& quat = msg->poses[i].pose.orientation;
496 Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
497 Ogre::Quaternion xquat = orientation * Ogre::Quaternion(quat.w, quat.x, quat.y, quat.z);
498 axes_vect[i]->setPosition(xpos);
499 axes_vect[i]->setOrientation(xquat);
505 for (uint32_t i = 0; i < num_points; ++i)
507 const geometry_msgs::Point& pos = msg->poses[i].pose.position;
508 const geometry_msgs::Quaternion& quat = msg->poses[i].pose.orientation;
509 Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
510 Ogre::Quaternion xquat = orientation * Ogre::Quaternion(quat.w, quat.x, quat.y, quat.z);
513 arrow_vect[i]->setColor(color.redF(), color.greenF(), color.blueF(), 1.0f);
519 arrow_vect[i]->setPosition(xpos);
520 arrow_vect[i]->setDirection(xquat * Ogre::Vector3(1, 0, 0));
An object that displays a multi-segment line strip rendered as billboards.
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
Displays a nav_msgs::Path message.
void setLineWidth(float width)
FloatProperty * alpha_property_
virtual QColor getColor() const
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
VectorProperty * offset_property_
void reset() override
Overridden from Display.
An arrow consisting of a cylinder and a cone.
EnumProperty * style_property_
EnumProperty * pose_style_property_
FloatProperty * line_width_property_
void destroyPoseArrowChain()
void show()
Show this Property in any PropertyTreeWidgets.
void destroyPoseAxesChain()
bool validateFloats(const sensor_msgs::CameraInfo &msg)
void updatePoseArrowGeometry()
#define ROS_WARN_ONCE_NAMED(name,...)
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
void setMaxPointsPerLine(uint32_t max)
FloatProperty * pose_arrow_head_length_property_
Property specialized to enforce floating point max/min.
void updatePoseAxisGeometry()
ColorProperty * color_property_
void hide()
Hide this Property in any PropertyTreeWidgets.
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)
#define ROS_DEBUG_NAMED(name,...)
ColorProperty * pose_arrow_color_property_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
bool validateQuaternions(const visualization_msgs::InteractiveMarker &marker)
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
void allocateArrowVector(std::vector< rviz::Arrow * > &arrow_vect, size_t num)
void setNumLines(uint32_t num)
FloatProperty * pose_arrow_head_diameter_property_
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
uint32_t messages_received_
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
void onInitialize() override
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.
virtual QString getName() const
Return the name of this Property as a QString.
void processMessage(const nav_msgs::Path::ConstPtr &msg) override
Overridden from MessageFilterDisplay.
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
void onInitialize() override
Overridden from Display.
FloatProperty * pose_axes_length_property_
std::vector< rviz::BillboardLine * > billboard_lines_
FloatProperty * pose_arrow_shaft_diameter_property_
virtual int getInt() const
Return the internal property value as an integer.
FloatProperty * pose_arrow_shaft_length_property_
void updateBufferLength()
std::vector< std::vector< rviz::Arrow * > > arrow_chain_
void allocateAxesVector(std::vector< rviz::Axes * > &axes_vect, size_t num)
std::vector< Ogre::ManualObject * > manual_objects_
FloatProperty * pose_axes_radius_property_
void updatePoseArrowColor()
virtual Ogre::Vector3 getVector() const
std::vector< std::vector< rviz::Axes * > > axes_chain_
IntProperty * buffer_length_property_
Ogre::ColourValue getOgreColor() const
void addPoint(const Ogre::Vector3 &point)
Property specialized to provide max/min enforcement for integers.
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Dec 13 2024 03:31:02