30 #include <boost/bind.hpp> 32 #include <OgreSceneNode.h> 33 #include <OgreSceneManager.h> 51 "The TF frame these axes will use for their origin.",
55 "Length of each axis, in meters.",
60 "Radius of each axis, in meters.",
97 std::string frame = qframe.toStdString();
99 Ogre::Vector3 position;
100 Ogre::Quaternion orientation;
118 "Could not transform from [" + qframe +
"] to Fixed Frame [" +
fixed_frame_ +
"] for an unknown reason" );
bool transformHasProblems(const std::string &frame, ros::Time time, std::string &error)
Check to see if a transform is known between a given frame and the fixed frame.
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
void onInitialize()
Override this function to do subclass-specific initialization.
virtual float getFloat() const
virtual void onEnable()
Derived classes override this to do the actual work of enabling themselves.
Property specialized to enforce floating point max/min.
virtual void setPosition(const Ogre::Vector3 &position)
Set the position of this object.
bool isEnabled() const
Return true if this Display is enabled, false if not.
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
virtual void onDisable()
Derived classes override this to do the actual work of disabling themselves.
void updateShape()
Update the length and radius of the axes object from property values.
virtual void update(float dt, float ros_dt)
Called periodically by the visualization manager.
FloatProperty * length_property_
TfFrameProperty * frame_property_
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
FloatProperty * radius_property_
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().
Axes * axes_
Handles actually drawing the axes.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
static const QString FIXED_FRAME_STRING
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.
void setFrameManager(FrameManager *frame_manager)
void set(float length, float radius)
Set the parameters on this object.
virtual void setOrientation(const Ogre::Quaternion &orientation)
Set the orientation of the object.
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this object.
Displays a set of XYZ axes at the origin of a chosen frame.
#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.