Marine systems simulation
WaypointRefGenTracker.h
1#ifndef WaypointRefGenTracker_h__
2#define WaypointRefGenTracker_h__
3
8#include <Eigen/Eigen>
9#include <Eigen/StdVector>
10
11#include <SimObject.h>
12
13#ifdef FH_VISUALIZATION
14 #include "sfh/ogre/C3DLine.h"
15#endif
16namespace Ship{
17 class WaypointRefGenTracker: public SimObject
18 {
19 public:
20
21 EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
22 WaypointRefGenTracker(const string& simObjectName, ISimObjectCreator* const creator);
23
24 const double * DesiredPosition(const double T, const double*const X);
25 const double * DesiredVelocity(const double T, const double *const X);
26 const double * DesiredHeading(const double T, const double *const X);
27 const double * DesiredYawRate(const double T, const double *const X);
28
29 void OdeFcn(const double T, const double *const X, double *const XDot, const bool IsMajorTimeStep);
30
31 void InitialConditionSetup(const double T, const double *const currentIC, double* const updatedIC, ISimObjectCreator* const creator);
32
33 std::vector<Eigen::Vector3d,Eigen::aligned_allocator<Eigen::Vector3d> > m_waypoints;
34 std::vector<Eigen::Vector3d,Eigen::aligned_allocator<Eigen::Vector3d> > straightStart;
35 std::vector<Eigen::Vector3d,Eigen::aligned_allocator<Eigen::Vector3d> > straightEnd;
36
37 std::vector<Eigen::Vector3d,Eigen::aligned_allocator<Eigen::Vector3d> > circleCenter;
38 std::vector<double> circleRadius;
39 std::vector<double> circleArcRadians;
40
41 std::vector<double> cummulativeLength;
42 std::vector<double> segmentLength;
43 std::vector<double> straightSegmentSpeed;
44 private:
45 unsigned int GetSegmentNumber(const double T,const double *const X) const;
46
47 Eigen::Vector3d GetCurrentTrackDirection(const double T,const double *const X) const;
48 Eigen::Vector3d GetCurrentTrackNormal(const double T,const double *const X) const;
49 double GetCurrentYawDesired(const double T,const double *const X) const;
50 double GetCurrentYawRateDesired(const double T,const double *const X) const;
51
52 Eigen::Vector3d GetCurrentTargetPoint(const double T,const double *const X) const;
53
54 ISignalPort *m_currentPosition;
55 ISignalPort *m_currentVelocity;
56
57 double m_desiredPosition[3];
58 double m_desiredHeading;
59 double m_desiedVelocity;
60 double m_desiredYawRate;
61
62 unsigned int m_trackState;
63 double m_lookaheadDistance;
64
65 int circleNoFromSegmentNo(int no)const {return no/2-1;}
66 int straightNoFromSegmentNo(int no)const {return (no-1)/2;}
67
68 #ifdef FH_VISUALIZATION
69 public:
70
71 C3DLine *sightline;
72 C3DLine *radline;
73 C3DLine *pathline;
74 C3DLine *removedlines;
75
76 Ogre::SceneNode ** m_legNodes;
77 Ogre::SceneNode ** m_circleNodes;
78 Ogre::SceneNode *m_targetNode;
79 void RenderInit(Ogre::Root* const ogreRoot, ISimObjectCreator* const creator);
80 void RenderUpdate(const double T, const double* const X);
81 #endif
82
83
84 };
85}
86#endif // WaypointRefGenTracker_h__
Definition: WaypointRefGenTracker.h:18
Simple waypoint object.
Definition: CableAttach.h:16