33 #include <OGRE/OgreSceneNode.h> 34 #include <OGRE/OgreSceneManager.h> 53 "Color to draw the spline.",
57 "Shape of the spline.",
64 "Number of points to display along path.",
70 "Scale of the spline contour.",
76 "Color to draw the spline orientation arrows.",
79 "Number of arrows to display along path.",
85 "Scale of the spline orientation arrows.",
91 "Number of prior measurements to display.",
124 for (
auto& visualsI:
visuals_ ) { visualsI->setPathColor ( color ); }
128 for (
auto& visualsI:
visuals_ ) { visualsI->setOrientColor ( color ); }
134 for (
auto& visualsI:
visuals_ ) { visualsI->setShape ( shape_type ); }
140 for (
auto& visualsI:
visuals_ ) { visualsI->setPathScale ( scale ); }
144 for (
auto& visualsI:
visuals_ ) { visualsI->setOrientScale ( scale ); }
154 for (
auto& visualsI:
visuals_ ) { visualsI->setPathPointsNr ( pointsNr ); }
158 for (
auto& visualsI:
visuals_ ) { visualsI->setOrientPointsNr ( pointsNr ); }
167 Ogre::Quaternion orientation;
168 Ogre::Vector3 position;
171 position, orientation ) ) {
172 ROS_DEBUG (
"Error transforming from frame '%s' to frame '%s'",
173 msg->header.frame_id.c_str(), qPrintable (
fixed_frame_ ) );
187 visual->setMessage ( msg );
188 visual->setFramePosition ( position );
189 visual->setFrameOrientation ( orientation );
void updatePathPointsNr()
boost::circular_buffer< boost::shared_ptr< SplineVisual > > visuals_
Ogre::ColourValue getOgreColor() const
virtual void onInitialize()
DisplayContext * context_
rviz::ColorProperty * color_path_property_
virtual int getInt() const
rviz::EnumProperty * shape_property_
virtual float getFloat() const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void updateOrientPointsNr()
rviz::IntProperty * points_nr_orient_property_
Ogre::SceneNode * scene_node_
rviz::IntProperty * history_length_property_
virtual FrameManager * getFrameManager() const =0
void addOptionStd(const std::string &option, int value=0)
void updateHistoryLength()
virtual void onInitialize()
rviz::FloatProperty * scale_path_property_
virtual Ogre::SceneManager * getSceneManager() const =0
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void processMessage(const tuw_nav_msgs::Spline::ConstPtr &msg)
rviz::ColorProperty * color_orient_property_
virtual int getOptionInt()
rviz::FloatProperty * scale_orient_property_
rviz::IntProperty * points_nr_path_property_