30 #include <OGRE/OgreSceneNode.h> 31 #include <OGRE/OgreSceneManager.h> 49 "Scale of the pose's pose.",
55 "Color to draw the pose's pose.",
59 "Color to draw the pose's variance.",
89 visual_->setScalePose ( scale );
95 visual_->setColorPose ( color );
101 visual_->setColorVariance ( color );
109 Ogre::Quaternion orientation;
110 Ogre::Vector3 position;
113 ROS_DEBUG (
"Error transforming from frame '%s' to frame '%s'",
114 msg->header.frame_id.c_str(), qPrintable (
fixed_frame_ ) );
120 visual_->setFramePosition ( position );
121 visual_->setFrameOrientation ( orientation );
void updateColorVariance()
PoseWithCovarianceDisplay()
Ogre::ColourValue getOgreColor() const
virtual void onInitialize()
rviz::ColorProperty * property_color_pose_
DisplayContext * context_
virtual float getFloat() const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Ogre::SceneNode * scene_node_
virtual void onInitialize()
virtual FrameManager * getFrameManager() const =0
void processMessage(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
rviz::FloatProperty * property_scale_pose_
virtual Ogre::SceneManager * getSceneManager() const =0
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
rviz::ColorProperty * property_color_variance_
virtual ~PoseWithCovarianceDisplay()
boost::shared_ptr< PoseWithCovarianceVisual > visual_