33 #ifndef ROUTESEGMENTS_VISUAL_H 34 #define ROUTESEGMENTS_VISUAL_H 36 #include <tuw_nav_msgs/RouteSegments.h> 38 #include <eigen3/unsupported/Eigen/Splines> 68 void setMessage(
const tuw_nav_msgs::RouteSegments::ConstPtr& msg );
75 void setFramePosition(
const Ogre::Vector3& position );
76 void setFrameOrientation(
const Ogre::Quaternion& orientation );
80 void setStartPointColor( Ogre::ColourValue color );
81 void setEndPointColor( Ogre::ColourValue color );
82 void setCenterPointColor( Ogre::ColourValue color );
83 void setLineColor( Ogre::ColourValue color );
84 void setArcColor( Ogre::ColourValue color );
94 void setStartPointScale(
float scale );
95 void setEndPointScale(
float scale );
96 void setCenterPointScale(
float scale );
98 void setShowArcs(
bool visible );
99 void setShowLines (
bool visible );
100 void setShowStartPoints(
bool visible );
101 void setShowEndPoints (
bool visible );
102 void setShowCenterPoints (
bool visible );
107 std::vector<boost::shared_ptr<rviz::Shape> >
endPts_;
109 std::vector<boost::shared_ptr<rviz::Line> >
lines_;
110 std::vector<boost::shared_ptr<rviz::Line> >
arcs_;
148 #endif // ROUTESEGMENTS_VISUAL_H Ogre::ColourValue color_center_point_
Ogre::SceneManager * scene_manager_
std::vector< boost::shared_ptr< rviz::Line > > arcs_
rviz::Shape::Type shape_start_point_
boost::shared_ptr< Eigen::Spline3d > spline_
rviz::Shape::Type shape_end_point_
std::vector< boost::shared_ptr< rviz::Shape > > startPts_
Ogre::ColourValue color_end_point_
Ogre::ColourValue color_lines_
Ogre::ColourValue color_start_point_
float scale_center_point_
TFSIMD_FORCE_INLINE Vector3()
Ogre::ColourValue color_arcs_
rviz::Shape::Type shape_center_point_
Ogre::SceneNode * frame_node_
std::vector< boost::shared_ptr< rviz::Line > > lines_
std::vector< boost::shared_ptr< rviz::Shape > > centerPts_
std::vector< boost::shared_ptr< rviz::Shape > > endPts_