30 #include <boost/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,
135 if (num > axes_vect.size())
137 for (
size_t i = axes_vect.size(); i < num; i++)
142 axes_vect.push_back(axes);
145 else if (num < axes_vect.size())
147 for (
int i = axes_vect.size() - 1; num <= i; i--)
151 axes_vect.resize(num);
157 if (num > arrow_vect.size())
159 for (
size_t i = arrow_vect.size(); i < num; i++)
162 arrow_vect.push_back(arrow);
165 else if (num < arrow_vect.size())
167 for (
int i = arrow_vect.size() - 1; num <= i; i--)
169 delete arrow_vect[i];
171 arrow_vect.resize(num);
274 std::vector<rviz::Axes*>& axes_vect =
axes_chain_[i];
275 for (
size_t j = 0; j < axes_vect.size(); j++)
289 std::vector<rviz::Arrow*>& arrow_vect =
arrow_chain_[i];
290 for (
size_t j = 0; j < arrow_vect.size(); j++)
292 arrow_vect[j]->setColor(color.redF(), color.greenF(), color.blueF(), 1.0f);
302 std::vector<rviz::Arrow*>& arrow_vect =
arrow_chain_[i];
303 for (
size_t j = 0; j < arrow_vect.size(); j++)
322 manual_object->clear();
324 manual_object =
nullptr;
334 delete billboard_line;
335 billboard_line =
nullptr;
360 Ogre::ManualObject* manual_object =
scene_manager_->createManualObject();
361 manual_object->setDynamic(
true);
394 Ogre::ManualObject* manual_object =
nullptr;
402 manual_object->clear();
407 billboard_line->
clear();
415 "Message contained invalid floating point values (nans or infs)");
422 "Path '%s' contains unnormalized quaternions. " 423 "This warning will only be output once but may be true for others; " 424 "enable DEBUG messages for ros.rviz.quaternions to see more details.",
430 Ogre::Vector3 position;
431 Ogre::Quaternion orientation;
434 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(),
438 Ogre::Matrix4 transform(orientation);
439 transform.setTrans(position);
447 uint32_t num_points = msg->poses.size();
453 manual_object->estimateVertexCount(num_points);
454 manual_object->begin(
"BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_STRIP);
455 for (uint32_t i = 0; i < num_points; ++i)
457 const geometry_msgs::Point& pos = msg->poses[i].pose.position;
458 Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
459 manual_object->position(xpos.x, xpos.y, xpos.z);
460 manual_object->colour(color);
463 manual_object->end();
471 for (uint32_t i = 0; i < num_points; ++i)
473 const geometry_msgs::Point& pos = msg->poses[i].pose.position;
474 Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
475 billboard_line->
addPoint(xpos, color);
483 std::vector<rviz::Arrow*>& arrow_vect =
arrow_chain_[bufferIndex];
484 std::vector<rviz::Axes*>& axes_vect =
axes_chain_[bufferIndex];
490 for (uint32_t i = 0; i < num_points; ++i)
492 const geometry_msgs::Point& pos = msg->poses[i].pose.position;
493 const geometry_msgs::Quaternion& quat = msg->poses[i].pose.orientation;
494 Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
495 Ogre::Quaternion xquat = orientation * Ogre::Quaternion(quat.w, quat.x, quat.y, quat.z);
496 axes_vect[i]->setPosition(xpos);
497 axes_vect[i]->setOrientation(xquat);
503 for (uint32_t i = 0; i < num_points; ++i)
505 const geometry_msgs::Point& pos = msg->poses[i].pose.position;
506 const geometry_msgs::Quaternion& quat = msg->poses[i].pose.orientation;
507 Ogre::Vector3 xpos = transform * Ogre::Vector3(pos.x, pos.y, pos.z);
508 Ogre::Quaternion xquat = orientation * Ogre::Quaternion(quat.w, quat.x, quat.y, quat.z);
511 arrow_vect[i]->setColor(color.redF(), color.greenF(), color.blueF(), 1.0f);
517 arrow_vect[i]->setPosition(xpos);
518 arrow_vect[i]->setDirection(xquat * Ogre::Vector3(1, 0, 0));
std::vector< Ogre::ManualObject * > manual_objects_
std::vector< rviz::BillboardLine * > billboard_lines_
void addPoint(const Ogre::Vector3 &point)
void updatePoseArrowColor()
FloatProperty * line_width_property_
ColorProperty * pose_arrow_color_property_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
An object that displays a multi-segment line strip rendered as billboards.
virtual QColor getColor() const
EnumProperty * style_property_
FloatProperty * pose_arrow_shaft_diameter_property_
FloatProperty * pose_arrow_head_diameter_property_
FloatProperty * pose_arrow_shaft_length_property_
VectorProperty * offset_property_
void reset() override
Overridden from Display.
virtual Ogre::Vector3 getVector() const
Ogre::ColourValue getOgreColor() const
FloatProperty * pose_axes_radius_property_
void allocateAxesVector(std::vector< rviz::Axes *> &axes_vect, int num)
Property specialized to enforce floating point max/min.
ColorProperty * color_property_
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.
void processMessage(const nav_msgs::Path::ConstPtr &msg) override
Overridden from MessageFilterDisplay.
Displays a nav_msgs::Path message.
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
void onInitialize() override
Overridden from Display.
#define ROS_DEBUG_NAMED(name,...)
bool validateFloats(const sensor_msgs::CameraInfo &msg)
virtual void addOption(const QString &option, int value=0)
void show()
Show this Property in any PropertyTreeWidgets.
std::vector< std::vector< rviz::Arrow * > > arrow_chain_
virtual QString getName() const
Return the name of this Property as a QString.
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
void updatePoseArrowGeometry()
void allocateArrowVector(std::vector< rviz::Arrow *> &arrow_vect, int num)
uint32_t messages_received_
void setNumLines(uint32_t num)
#define ROS_WARN_ONCE_NAMED(name,...)
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
void setMaxPointsPerLine(uint32_t max)
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
FloatProperty * alpha_property_
virtual int getInt() const
Return the internal property value as an integer.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
IntProperty * buffer_length_property_
bool validateQuaternions(const visualization_msgs::InteractiveMarker &marker)
virtual float getFloat() const
std::vector< std::vector< rviz::Axes * > > axes_chain_
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.
EnumProperty * pose_style_property_
void onInitialize() override
An arrow consisting of a cylinder and a cone.
void destroyPoseArrowChain()
void destroyPoseAxesChain()
void hide()
Hide this Property in any PropertyTreeWidgets.
void updatePoseAxisGeometry()
void updateBufferLength()
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
FloatProperty * pose_arrow_head_length_property_
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
FloatProperty * pose_axes_length_property_
void setLineWidth(float width)