30 #include <OgreManualObject.h> 31 #include <OgreSceneManager.h> 32 #include <OgreSceneNode.h> 60 Ogre::Vector3 vectorRosToOgre(geometry_msgs::Point
const& point)
62 return Ogre::Vector3(point.x, point.y, point.z);
65 Ogre::Quaternion quaternionRosToOgre(geometry_msgs::Quaternion
const& quaternion)
82 new FloatProperty(
"Alpha", 1,
"Amount of transparency to apply to the displayed poses.",
this,
89 new FloatProperty(
"Head Radius", 0.03,
"Radius of the arrow's head, in meters.",
this,
93 new FloatProperty(
"Head Length", 0.07,
"Length of the arrow's head, in meters.",
this,
97 new FloatProperty(
"Shaft Radius", 0.01,
"Radius of the arrow's shaft, in meters.",
this,
101 new FloatProperty(
"Shaft Length", 0.23,
"Length of the arrow's shaft, in meters.",
this,
146 "Message contained invalid floating point values (nans or infs)");
153 "PoseArray msg received on topic '%s' contains unnormalized quaternions. " 154 "This warning will only be output once but may be true for others; " 155 "enable DEBUG messages for ros.rviz.quaternions to see more details.",
158 "PoseArray msg received on topic '%s' contains unnormalized quaternions.",
168 poses_.resize(msg->poses.size());
169 for (std::size_t i = 0; i < msg->poses.size(); ++i)
171 poses_[i].position = vectorRosToOgre(msg->poses[i].position);
172 poses_[i].orientation = quaternionRosToOgre(msg->poses[i].orientation);
181 Ogre::Vector3 position;
182 Ogre::Quaternion orientation;
185 ROS_ERROR(
"Error transforming pose '%s' from frame '%s' to frame '%s'", qPrintable(
getName()),
201 size_t num_poses =
poses_.size();
203 manual_object_->begin(
"BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_LIST);
204 for (
size_t i = 0; i < num_poses; ++i)
206 const Ogre::Vector3& pos =
poses_[i].position;
207 const Ogre::Quaternion& orient =
poses_[i].orientation;
208 Ogre::Vector3 vertices[6];
210 vertices[1] = pos + orient * Ogre::Vector3(length, 0, 0);
211 vertices[2] = vertices[1];
212 vertices[3] = pos + orient * Ogre::Vector3(0.75 * length, 0.2 * length, 0);
213 vertices[4] = vertices[1];
214 vertices[5] = pos + orient * Ogre::Vector3(0.75 * length, -0.2 * length, 0);
216 for (
int i = 0; i < 6; ++i)
230 case ShapeType::Arrow2d:
235 case ShapeType::Arrow3d:
240 case ShapeType::Axes:
255 Ogre::Quaternion adjust_orientation(Ogre::Degree(-90), Ogre::Vector3::UNIT_Y);
256 for (std::size_t i = 0; i <
poses_.size(); ++i)
259 arrows3d_[i].setOrientation(
poses_[i].orientation * adjust_orientation);
269 for (std::size_t i = 0; i <
poses_.size(); ++i)
310 bool use_arrow2d = shape == ShapeType::Arrow2d;
311 bool use_arrow3d = shape == ShapeType::Arrow3d;
312 bool use_arrow = use_arrow2d || use_arrow3d;
313 bool use_axes = shape == ShapeType::Axes;
338 if (shape == ShapeType::Arrow2d)
342 else if (shape == ShapeType::Arrow3d)
344 for (std::size_t i = 0; i <
arrows3d_.size(); ++i)
360 for (std::size_t i = 0; i <
poses_.size(); ++i)
372 for (std::size_t i = 0; i <
poses_.size(); ++i)
FloatProperty * arrow3d_head_length_property_
void reset() override
Called to tell the display to clear its state.
void updateAxesGeometry()
Update the axes geometry.
void updateShapeChoice()
Update the interface and visible shapes based on the selected shape type.
ColorProperty * arrow_color_property_
FloatProperty * arrow2d_length_property_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
bool setTransform(std_msgs::Header const &header)
Displays a geometry_msgs/PoseArray message as a bunch of line-drawn arrows.
Ogre::ColourValue getOgreColor() const
RosTopicProperty * topic_property_
FloatProperty * axes_radius_property_
void updateArrow2dGeometry()
Update the flat arrow geometry.
Property specialized to enforce floating point max/min.
std::string getTopicStd() const
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().
FloatProperty * arrow3d_shaft_radius_property_
#define ROS_DEBUG_NAMED(name,...)
std::vector< OgrePose > poses_
FloatProperty * arrow_alpha_property_
bool validateFloats(const sensor_msgs::CameraInfo &msg)
virtual void addOption(const QString &option, int value=0)
void onInitialize() override
Override this function to do subclass-specific initialization.
void updateArrowColor()
Update the arrow color.
~PoseArrayDisplay() override
virtual QString getName() const
Return the name of this Property as a QString.
void processMessage(const geometry_msgs::PoseArray::ConstPtr &msg) override
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
FloatProperty * axes_length_property_
FloatProperty * arrow3d_shaft_length_property_
float normalizeQuaternion(float &w, float &x, float &y, float &z)
#define ROS_WARN_ONCE_NAMED(name,...)
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
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.
bool validateQuaternions(const visualization_msgs::InteractiveMarker &marker)
virtual float getFloat() const
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 * shape_property_
void onInitialize() override
void updateArrow3dGeometry()
Update the 3D arrow geometry.
An arrow consisting of a cylinder and a cone.
boost::ptr_vector< Arrow > arrows3d_
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
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. Values are in the range [0, 1].
bool initialized() const
Returns true if the display has been initialized.
Ogre::SceneNode * arrow_node_
FloatProperty * arrow3d_head_radius_property_
boost::ptr_vector< Axes > axes_
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)
Ogre::ManualObject * manual_object_
Ogre::SceneNode * axes_node_
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.