33 #include <OGRE/OgreSceneNode.h> 34 #include <OGRE/OgreSceneManager.h> 53 "Color to draw the path.",
64 "Scale of the path contour.",
70 "Color to draw the path orientation arrows.",
73 "Distance between pose arrows [m]",
74 this, SLOT ( updateOrientPointsNr() ) );
79 "Scale of the path orientation arrows.",
85 "Number of prior measurements to display.",
118 for (
auto& visualsI:
visuals_ ) { visualsI->setPathColor ( color ); }
122 for (
auto& visualsI:
visuals_ ) { visualsI->setOrientColor ( color ); }
128 for (
auto& visualsI:
visuals_ ) { visualsI->setShape ( shape_type ); }
134 for (
auto& visualsI:
visuals_ ) { visualsI->setPathScale ( scale ); }
138 for (
auto& visualsI:
visuals_ ) { visualsI->setOrientScale ( scale ); }
148 for (
auto& visualsI:
visuals_ ) { visualsI->setOrientDeltaS ( deltaS ); }
157 Ogre::Quaternion orientation;
158 Ogre::Vector3 position;
161 position, orientation ) ) {
162 ROS_DEBUG (
"Error transforming from frame '%s' to frame '%s'",
163 msg->header.frame_id.c_str(), qPrintable (
fixed_frame_ ) );
177 visual->setMessage ( msg );
178 visual->setFramePosition ( position );
179 visual->setFrameOrientation ( orientation );
rviz::FloatProperty * scale_path_property_
Ogre::ColourValue getOgreColor() const
virtual void onInitialize()
rviz::EnumProperty * shape_property_
DisplayContext * context_
rviz::FloatProperty * path_delta_s_orient_property_
virtual int getInt() const
virtual float getFloat() const
rviz::IntProperty * history_length_property_
rviz::ColorProperty * color_path_property_
Ogre::SceneNode * scene_node_
rviz::FloatProperty * scale_orient_property_
rviz::ColorProperty * color_orient_property_
boost::circular_buffer< boost::shared_ptr< PathVisual > > visuals_
virtual FrameManager * getFrameManager() const =0
void addOptionStd(const std::string &option, int value=0)
virtual Ogre::SceneManager * getSceneManager() const =0
void updateOrientDeltaS()
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
virtual void onInitialize()
void updateHistoryLength()
virtual int getOptionInt()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void processMessage(const nav_msgs::Path::ConstPtr &msg)