33 #include <OGRE/OgreSceneNode.h> 34 #include <OGRE/OgreSceneManager.h> 112 "Number of prior measurements to display.",
151 for (
auto& visualsI:
visuals_ ) { visualsI->setStartPointShape ( shape_type ); }
168 for (
auto& visualsI:
visuals_ ) { visualsI->setEndPointShape ( shape_type ); }
184 for (
auto& visualsI:
visuals_ ) { visualsI->setCenterPointShape ( shape_type ); }
237 Ogre::Quaternion orientation;
238 Ogre::Vector3 position;
241 position, orientation ) ) {
242 ROS_DEBUG (
"Error transforming from frame '%s' to frame '%s'",
243 msg->header.frame_id.c_str(), qPrintable (
fixed_frame_ ) );
257 visual->setMessage ( msg );
258 visual->setFramePosition ( position );
259 visual->setFrameOrientation ( orientation );
rviz::BoolProperty * show_lines_property_
virtual void onInitialize()
rviz::BoolProperty * show_start_point_
void updateStartPointColor()
Ogre::ColourValue getOgreColor() const
rviz::BoolProperty * show_end_point_
virtual void onInitialize()
DisplayContext * context_
virtual int getInt() const
rviz::EnumProperty * shape_end_point_
rviz::EnumProperty * shape_start_point_
virtual float getFloat() const
boost::circular_buffer< boost::shared_ptr< RouteSegmentsVisual > > visuals_
rviz::FloatProperty * scale_start_point_
void updateShowEndPoints()
void updateEndPointShape()
Ogre::SceneNode * scene_node_
rviz::BoolProperty * show_center_point_
virtual bool getBool() const
void updateShowStartPoints()
rviz::FloatProperty * scale_center_point_
void updateStartPointShape()
rviz::ColorProperty * color_center_point_
rviz::ColorProperty * color_lines_
rviz::BoolProperty * show_arcs_property_
virtual FrameManager * getFrameManager() const =0
void addOptionStd(const std::string &option, int value=0)
void updateEndPointColor()
rviz::ColorProperty * color_end_point_
virtual Ogre::SceneManager * getSceneManager() const =0
rviz::EnumProperty * shape_center_point_
void updateEndPointScale()
void updateHistoryLength()
void updateCenterPointShape()
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void updateCenterPointColor()
void processMessage(const tuw_nav_msgs::RouteSegments::ConstPtr &msg)
rviz::IntProperty * history_length_property_
virtual ~RouteSegmentsDisplay()
void updateStartPointScale()
virtual int getOptionInt()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rviz::FloatProperty * scale_end_point_
void updateShowCenterPoints()
void updateCenterPointScale()
rviz::ColorProperty * color_arcs_
rviz::ColorProperty * color_start_point_