30 #include <OgreEntity.h> 31 #include <OgreSceneNode.h> 93 void setMessage(
const geometry_msgs::PoseStampedConstPtr& message)
103 Ogre::Vector3(message->pose.position.x, message->pose.position.y, message->pose.position.z));
105 Ogre::Quaternion(message->pose.orientation.w, message->pose.orientation.x,
106 message->pose.orientation.y, message->pose.orientation.z));
133 "Shaft Length", 1,
"Length of the arrow's shaft, in meters.",
this, SLOT(
updateArrowGeometry()));
137 new FloatProperty(
"Shaft Radius", 0.05,
"Radius of the arrow's shaft, in meters.",
this,
253 "Message contained invalid floating point values (nans or infs)");
260 "Pose '%s' contains unnormalized quaternions. " 261 "This warning will only be output once but may be true for others; " 262 "enable DEBUG messages for ros.rviz.quaternions to see more details.",
267 Ogre::Vector3 position;
268 Ogre::Quaternion orientation;
271 ROS_ERROR(
"Error transforming pose '%s' from frame '%s' to frame '%s'", qPrintable(
getName()),
272 message->header.frame_id.c_str(), qPrintable(
fixed_frame_));
FloatProperty * shaft_radius_property_
void onInitialize() override
Override this function to do subclass-specific initialization.
friend class PoseDisplaySelectionHandler
virtual bool setVector(const Ogre::Vector3 &vector)
FloatProperty * axes_length_property_
StringProperty * frame_property_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
PoseDisplaySelectionHandlerPtr coll_handler_
A single element of a property tree, with a name, value, description, and possibly children...
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
Ogre::ColourValue getOgreColor() const
void getAABBs(const Picked &, V_AABB &aabbs) override
Property specialized to enforce floating point max/min.
void set(float shaft_length, float shaft_diameter, float head_length, float head_diameter)
Set the parameters for this arrow.
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
FloatProperty * shaft_length_property_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Accumulates and displays the pose from a geometry_msgs::PoseStamped message.
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this arrow.
VectorProperty * position_property_
void onEnable() override
Overridden from MessageFilterDisplay to get arrow/axes visibility correct.
void setMessage(const geometry_msgs::PoseStampedConstPtr &message)
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
#define ROS_DEBUG_NAMED(name,...)
void updateShapeVisibility()
Pure-virtual base class for objects which give Display subclasses context in which to work...
std::vector< Ogre::AxisAlignedBox > V_AABB
bool validateFloats(const sensor_msgs::CameraInfo &msg)
FloatProperty * alpha_property_
virtual void addOption(const QString &option, int value=0)
void updateArrowGeometry()
QuaternionProperty * orientation_property_
virtual QString getName() const
Return the name of this Property as a QString.
virtual bool setQuaternion(const Ogre::Quaternion &quaternion)
void createProperties(const Picked &, Property *parent_property) override
Override to create properties of the given picked object(s).
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.
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
FloatProperty * head_length_property_
ColorProperty * color_property_
#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().
void reset() override
Called to tell the display to clear its state.
void updateAxisGeometry()
EnumProperty * shape_property_
virtual void setHidden(bool hidden)
Hide or show this property in any PropertyTreeWidget viewing its parent.
Property specialized for string values.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
void processMessage(const geometry_msgs::PoseStamped::ConstPtr &message) override
void updateColorAndAlpha()
bool validateQuaternions(const visualization_msgs::InteractiveMarker &marker)
FloatProperty * axes_radius_property_
virtual float getFloat() const
QList< Property * > properties_
void onInitialize() override
An arrow consisting of a cylinder and a cone.
void set(float length, float radius)
Set the parameters on this object.
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation.
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 * getSceneNode()
Get the scene node associated with this object.
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
bool setStdString(const std::string &std_str)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
FloatProperty * head_radius_property_
PoseDisplaySelectionHandler(PoseDisplay *display, DisplayContext *context)
Ogre::Entity * getEntity()