33 #ifndef SPLINE_VISUAL_H 34 #define SPLINE_VISUAL_H 36 #include <tuw_nav_msgs/Spline.h> 38 #include <eigen3/unsupported/Eigen/Splines> 61 SplineVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );
67 void setMessage(
const tuw_nav_msgs::Spline::ConstPtr& msg );
74 void setFramePosition(
const Ogre::Vector3& position );
75 void setFrameOrientation(
const Ogre::Quaternion& orientation );
79 void setPathColor( Ogre::ColourValue color );
80 void setOrientColor( Ogre::ColourValue color );
88 void setPathScale(
float scale );
89 void setOrientScale(
float scale );
92 void setPathPointsNr(
int pointsNr );
93 void setOrientPointsNr(
int pointsNr );
127 #endif // SPLINE_VISUAL_H
Ogre::SceneNode * frame_node_
Ogre::ColourValue colorOrient_
TFSIMD_FORCE_INLINE Vector3()
std::vector< boost::shared_ptr< rviz::Arrow > > splinePtsTheta_
Ogre::ColourValue colorPath_
rviz::Shape::Type shape_type_
boost::shared_ptr< Eigen::Spline3d > spline_
Ogre::SceneManager * scene_manager_
std::vector< boost::shared_ptr< rviz::Shape > > splinePtsXY_