33 #ifndef SPLINE_VISUAL_H 34 #define SPLINE_VISUAL_H 36 #include <tuw_nav_msgs/Spline.h> 38 #include <eigen3/unsupported/Eigen/Splines> 40 #include <tuw_control/state/state_sim_template.hpp> 56 public :
enum class StateVars { SIGMA, ARC, ENUM_SIZE };
62 public : StateSimUPtr cloneStateSim ()
const override;
63 public :
double stateArc ()
const override;
64 public :
double stateDist ()
const override;
65 public : ParamFuncs* paramFuncs ()
override;
66 public : ParamFuncsDist* paramFuncsDist ()
override;
68 private :
void setStateCf (
const double& _arc,
const ParamFuncs::EvalArcGuarantee& _evalArcGuarantee = ParamFuncs::EvalArcGuarantee::AFTER_LAST )
override;
69 private : State&
stateNmDelta (
const double& _dArc )
override {
throw "not implemented"; }
70 private : State& stateNmDot ()
override;
86 SplineVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );
92 void setMessage(
const tuw_nav_msgs::Spline::ConstPtr& msg );
99 void setFramePosition(
const Ogre::Vector3& position );
100 void setFrameOrientation(
const Ogre::Quaternion& orientation );
104 void setPathColor( Ogre::ColourValue color );
105 void setOrientColor( Ogre::ColourValue color );
113 void setPathScale (
float scale );
114 void setOrientScale(
float scale );
116 void setPathDs (
float _ds );
117 void setOrientDs (
float _ds );
154 #endif // SPLINE_VISUAL_H
rviz::Shape::Type shape_type_
Ogre::SceneNode * frame_node_
Ogre::ColourValue colorOrient_
std::vector< boost::shared_ptr< rviz::Arrow > > splinePtsTheta_
Ogre::ColourValue colorPath_
boost::shared_ptr< Eigen::Spline3d > spline3d_
Parametric functions with closed-form distance evaluation structure.
std::vector< double > sigmaXYLattice_
State & stateNmDelta(const double &_dArc) override
std::vector< double > sigmaThetaLattice_
std::shared_ptr< tuw::MetricSplineSim > metricSplineSim_
boost::shared_ptr< Eigen::Spline3d > spline_
std::vector< boost::shared_ptr< rviz::Shape > > splinePtsXY_
TFSIMD_FORCE_INLINE Vector3()
Ogre::SceneManager * scene_manager_