19 #ifndef __UUV_GAZEBO_PLUGINS_LIFT_DRAG_MODEL_HH__ 20 #define __UUV_GAZEBO_PLUGINS_LIFT_DRAG_MODEL_HH__ 25 #include <gazebo/gazebo.hh> 39 const std::string& element);
45 public:
virtual std::string
GetType() = 0;
48 public:
virtual ignition::math::Vector3d
compute(
49 const ignition::math::Vector3d &_velL) = 0;
52 public:
virtual bool GetParam(std::string _tag,
56 public:
virtual std::map<std::string, double>
GetListParams() = 0;
66 typedef LiftDrag* (*LiftDragCreator)(sdf::ElementPtr);
72 public:
LiftDrag* CreateLiftDrag(sdf::ElementPtr _sdf);
78 public:
bool RegisterCreator(
const std::string& _identifier,
85 private: std::map<std::string, LiftDragCreator>
creators_;
89 #define REGISTER_LIFTDRAG(type) static const bool registeredWithFactory 92 #define REGISTER_LIFTDRAG_CREATOR(type, creator) \ 93 const bool type::registeredWithFactory = \ 94 LiftDragFactory::GetInstance().RegisterCreator( \ 95 type::IDENTIFIER, creator); 103 public:
static LiftDrag* create(sdf::ElementPtr _sdf);
106 public:
virtual std::string
GetType() {
return IDENTIFIER; }
109 public:
virtual ignition::math::Vector3d
compute(
const ignition::math::Vector3d &velL);
115 public:
virtual bool GetParam(std::string _tag,
double& _output);
118 public:
virtual std::map<std::string, double>
GetListParams();
131 :
LiftDrag(), liftConstant(_liftConstant), dragConstant(_dragConstant) {}
141 public:
static LiftDrag* create(sdf::ElementPtr _sdf);
144 public:
virtual std::string
GetType() {
return IDENTIFIER; }
147 public:
virtual ignition::math::Vector3d
compute(
const ignition::math::Vector3d &_velL);
156 public:
virtual bool GetParam(std::string _tag,
double& _output);
159 public:
virtual std::map<std::string, double>
GetListParams();
168 protected:
double a0;
187 double _alphaStall,
double _cla,
double _claStall,
188 double _cda,
double _cdaStall)
189 :
LiftDrag(), area(_area), fluidDensity(_fluidDensity),
190 a0(_a0), alphaStall(_alphaStall),
191 cla(_cla), claStall(_claStall),
192 cda(_cda), cdaStall(_cdaStall) {}
double cdaStall
Drag coefficient with stall.
virtual ~LiftDrag()
Destructor.
double prevTime
Time of last state update.
double fluidDensity
Fluid density.
double liftConstant
Lift constant.
double a0
Original zero angle of attack location.
virtual std::string GetType()
Return (derived) type of dynamic system.
LiftDragTwoLines(double _area, double _fluidDensity, double _a0, double _alphaStall, double _cla, double _claStall, double _cda, double _cdaStall)
Constructor.
static const std::string IDENTIFIER
Unique identifier for this dynamical model.
Lift&drag model that models lift/drag coeffs using two lines. This is based on Gazebo's LiftDragPlugin bu...
Abstract base class for Lift&Drag models.
double alphaStall
Stall angle.
virtual std::map< std::string, double > GetListParams()=0
Return list of all parameters.
virtual bool GetParam(std::string _tag, double &_output)=0
Return paramater in vector form for the given tag.
virtual std::string GetType()
Return (derived) type of dynamic system.
virtual std::string GetType()=0
Return (derived) type of lift&drag model.
LiftDragQuadratic(double _liftConstant, double _dragConstant)
Constructor.
double cda
Drag coefficient without stall.
LiftDrag *(* LiftDragCreator)(sdf::ElementPtr)
Function pointer to create a certain LiftDrag object.
LiftDrag()
Protected constructor: Use the factory for object creation.
double dragConstant
Drag constant.
std::map< std::string, LiftDragCreator > creators_
Map of each registered identifier to its corresponding creator.
static const std::string IDENTIFIER
Unique identifier for this dynamical model.
double state
Latest state.
Basic quadratic (Hugin) lift&drag model, page 18 from [1]. [1] Engelhardtsen, Øystein. "3D AUV Collision Avoidance." (2007).
Factory singleton class that creates a LiftDrag from sdf.
#define REGISTER_LIFTDRAG(type)
Use the following macro within a LiftDrag declaration:
double claStall
Lift coefficient with stall.
static bool CheckForElement(sdf::ElementPtr _sdf, const std::string &element)
Check for element. Complain and return 0 if it is missing.
double cla
Lift coefficient without stall.
virtual ignition::math::Vector3d compute(const ignition::math::Vector3d &_velL)=0
Compute the lift and drag force.
LiftDragFactory()
Constructor is private since this is a singleton.