30 #ifndef RVIZ_POSE_ARRAY_DISPLAY_H_ 31 #define RVIZ_POSE_ARRAY_DISPLAY_H_ 33 #include <geometry_msgs/PoseArray.h> 37 #include <boost/ptr_container/ptr_vector.hpp> 62 virtual void onInitialize();
64 virtual void processMessage(
const geometry_msgs::PoseArray::ConstPtr& msg );
67 bool setTransform(std_msgs::Header
const & header);
68 void updateArrows2d();
69 void updateArrows3d();
73 Arrow * makeArrow3d();
104 void updateShapeChoice();
107 void updateArrowColor();
110 void updateArrow2dGeometry();
113 void updateArrow3dGeometry();
116 void updateAxesGeometry();
FloatProperty * arrow3d_head_length_property_
ColorProperty * arrow_color_property_
Ogre::Quaternion orientation
FloatProperty * arrow2d_length_property_
Displays a geometry_msgs/PoseArray message as a bunch of line-drawn arrows.
FloatProperty * axes_radius_property_
Property specialized to enforce floating point max/min.
FloatProperty * arrow3d_shaft_radius_property_
std::vector< OgrePose > poses_
FloatProperty * arrow_alpha_property_
Display subclass using a tf::MessageFilter, templated on the ROS message type.
FloatProperty * axes_length_property_
FloatProperty * arrow3d_shaft_length_property_
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
EnumProperty * shape_property_
An arrow consisting of a cylinder and a cone.
boost::ptr_vector< Arrow > arrows3d_
Ogre::SceneNode * arrow_node_
FloatProperty * arrow3d_head_radius_property_
boost::ptr_vector< Axes > axes_
Ogre::ManualObject * manual_object_
Ogre::SceneNode * axes_node_