1 #include <OgreVector3.h> 2 #include <OgreSceneNode.h> 3 #include <OgreSceneManager.h> 48 Ogre::Vector3 point(msg->point.x, msg->point.y, msg->point.z);
Ogre::SceneNode * frame_node_
void setScale(const Ogre::Vector3 &scale) override
Set the scale of the object. Always relative to the identity orientation of the object.
void setColor(float r, float g, float b, float a) override
Set the color of the object. Values are in the range [0, 1].
void setColor(float r, float g, float b, float a)
void setMessage(const geometry_msgs::PointStamped::ConstPtr &msg)
void setPosition(const Ogre::Vector3 &position) override
Set the position of this object.
Ogre::SceneManager * scene_manager_
PointStampedVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node)
void setFramePosition(const Ogre::Vector3 &position)
void setFrameOrientation(const Ogre::Quaternion &orientation)
virtual ~PointStampedVisual()