Classes | Typedefs | Functions
gazebo Namespace Reference

Classes

class  BuoyantObject
 Class describing the dynamics of a buoyant object, useful for simple representations of underwater structures. More...
 
class  ConversionFunction
 Abstact base class for a thruster conversion function. More...
 
class  ConversionFunctionBasic
 The most basic conversion function: Thrust = const.*w*abs(w) This corresponds to what is attrributed to Yoerger et al. and called Model 1 in Bessa et al.: Dynamic Positioning of Underwater Robotic Vehicles with Thruster Dynamics Compensation. More...
 
class  ConversionFunctionBessa
 Asymmetric conversion function with dead-zone nonlinearity. This corresponds to what is called Model 2 in Bessa et al.: Dynamic Positioning of Underwater Robotic Vehicles with Thruster Dynamics Compensation. More...
 
class  ConversionFunctionFactory
 Factory singleton class that creates a ConversionFunction from sdf. More...
 
class  ConversionFunctionLinearInterp
 Conversion using linear interpolation between given data points. More...
 
class  Dynamics
 Abstract base class for thruster dynamics. More...
 
class  DynamicsFactory
 Factory singleton class that creates a ThrusterDynamics from sdf. More...
 
class  DynamicsFirstOrder
 First-order dynamic system. More...
 
class  DynamicsZeroOrder
 Trivial (no dynamics) zero-order dynamic system. More...
 
class  FinPlugin
 
class  HMBox
 Class containing the methods and attributes for a hydrodynamic model for a box in the fluid. More...
 
class  HMCylinder
 Class containing the methods and attributes for a hydrodynamic model for a cylinder in the fluid. More...
 
class  HMFossen
 Class containting the methods and attributes for a Fossen robot-like hydrodynamic model. The restoring forces are applied by the BuoyantObject class methods. Using the plugin for UUV models will use both this and the buoyant object class definitions, therefore the restoring forces were not inherited here. References: More...
 
class  HMSphere
 Class containing the methods and attributes for a hydrodynamic model for a sphere in the fluid. More...
 
class  HMSpheroid
 Class containing the methods and attributes for a hydrodynamic model for a spheroid in the fluid Reference: Antonelli - Underwater Robots. More...
 
class  HydrodynamicModel
 
class  HydrodynamicModelFactory
 Factory singleton class that creates a HydrodynamicModel from sdf. More...
 
class  LiftDrag
 Abstract base class for Lift&Drag models. More...
 
class  LiftDragFactory
 Factory singleton class that creates a LiftDrag from sdf. More...
 
class  LiftDragQuadratic
 Basic quadratic (Hugin) lift&drag model, page 18 from [1]. [1] Engelhardtsen, Øystein. "3D AUV Collision Avoidance." (2007). More...
 
class  LiftDragTwoLines
 Lift&drag model that models lift/drag coeffs using two lines. This is based on Gazebo's LiftDragPlugin but implemented as a derived LiftDrag model to allow using it in combination with the dynamics of a Fin. More...
 
class  ThrusterDynamicsBessa
 Bessa's dynamic thruster model. More...
 
class  ThrusterDynamicsYoerger
 Yoerger's dynamic thruster model. More...
 
class  ThrusterPlugin
 Class for the thruster plugin. More...
 
class  UmbilicalModel
 
class  UmbilicalModelBerg
 
class  UmbilicalModelFactory
 Factory singleton class that creates an UmbilicalModel from sdf. More...
 
class  UmbilicalPlugin
 
class  UmbilicalSegment
 
class  UnderwaterObjectPlugin
 Gazebo model plugin class for underwater objects. More...
 

Typedefs

typedef const boost::shared_ptr< const uuv_gazebo_plugins_msgs::msgs::Double > ConstDoublePtr
 Definition of a pointer to the floating point message. More...
 
typedef ConversionFunction *(* ConversionFunctionCreator) (sdf::ElementPtr)
 Function pointer to create a certain conversion function. More...
 
typedef Dynamics *(* DynamicsCreator) (sdf::ElementPtr)
 Function pointer to create a certain thruster dynamics object. More...
 
typedef HydrodynamicModel *(* HydrodynamicModelCreator) (sdf::ElementPtr, physics::LinkPtr)
 Function pointer to create a certain a model. More...
 
typedef boost::shared_ptr< HydrodynamicModelHydrodynamicModelPtr
 Pointer to model. More...
 
typedef LiftDrag *(* LiftDragCreator) (sdf::ElementPtr)
 Function pointer to create a certain LiftDrag object. More...
 
typedef UmbilicalModel *(* UmbilicalModelCreator) (sdf::ElementPtr, physics::ModelPtr)
 Function pointer to create a certain conversion function. More...
 
typedef boost::shared_ptr< UmbilicalSegmentUmbilicalSegmentPtr
 

Functions

Eigen::Matrix3d CrossProductOperator (Eigen::Vector3d _x)
 Returns the cross product operator matrix for Eigen vectors. More...
 
Eigen::Matrix3d CrossProductOperator (ignition::math::Vector3d _x)
 Returns the cross product operator matrix for Gazebo vectors. More...
 
Eigen::Vector6d EigenStack (const ignition::math::Vector3d &_x, const ignition::math::Vector3d &_y)
 
 GZ_REGISTER_MODEL_PLUGIN (UmbilicalPlugin)
 
ignition::math::Matrix3d Mat3dToGazebo (const Eigen::Matrix3d &_x)
 
 REGISTER_CONVERSIONFUNCTION_CREATOR (ConversionFunctionBasic,&ConversionFunctionBasic::create) ConversionFunction *ConversionFunctionBasic
 
 REGISTER_CONVERSIONFUNCTION_CREATOR (ConversionFunctionBessa,&ConversionFunctionBessa::create) ConversionFunction *ConversionFunctionBessa
 
 REGISTER_CONVERSIONFUNCTION_CREATOR (ConversionFunctionLinearInterp,&ConversionFunctionLinearInterp::create) ConversionFunction *ConversionFunctionLinearInterp
 
 REGISTER_DYNAMICS_CREATOR (DynamicsZeroOrder,&DynamicsZeroOrder::create) Dynamics *DynamicsZeroOrder
 
 REGISTER_DYNAMICS_CREATOR (DynamicsFirstOrder,&DynamicsFirstOrder::create) Dynamics *DynamicsFirstOrder
 
 REGISTER_DYNAMICS_CREATOR (ThrusterDynamicsYoerger,&ThrusterDynamicsYoerger::create) Dynamics *ThrusterDynamicsYoerger
 
 REGISTER_DYNAMICS_CREATOR (ThrusterDynamicsBessa,&ThrusterDynamicsBessa::create) Dynamics *ThrusterDynamicsBessa
 
 REGISTER_HYDRODYNAMICMODEL_CREATOR (HMFossen,&HMFossen::create)
 
 REGISTER_HYDRODYNAMICMODEL_CREATOR (HMSphere,&HMSphere::create)
 
 REGISTER_HYDRODYNAMICMODEL_CREATOR (HMCylinder,&HMCylinder::create)
 
 REGISTER_HYDRODYNAMICMODEL_CREATOR (HMSpheroid,&HMSpheroid::create)
 
 REGISTER_HYDRODYNAMICMODEL_CREATOR (HMBox,&HMBox::create)
 
 REGISTER_LIFTDRAG_CREATOR (LiftDragQuadratic,&LiftDragQuadratic::create) LiftDrag *LiftDragQuadratic
 
 REGISTER_LIFTDRAG_CREATOR (LiftDragTwoLines,&LiftDragTwoLines::create) LiftDrag *LiftDragTwoLines
 
std::vector< double > Str2Vector (std::string _input)
 Conversion of a string to a double vector. More...
 
Eigen::Vector3d ToEigen (const ignition::math::Vector3d &_x)
 
Eigen::Matrix3d ToEigen (const ignition::math::Matrix3d &_x)
 
ignition::math::Vector3d Vec3dToGazebo (const Eigen::Vector3d &_x)
 

Typedef Documentation

typedef const boost::shared_ptr< const uuv_gazebo_plugins_msgs::msgs::Double > gazebo::ConstDoublePtr

Definition of a pointer to the floating point message.

Definition at line 36 of file FinPlugin.hh.

typedef ConversionFunction*(* gazebo::ConversionFunctionCreator) (sdf::ElementPtr)

Function pointer to create a certain conversion function.

Definition at line 55 of file ThrusterConversionFcn.hh.

typedef Dynamics*(* gazebo::DynamicsCreator) (sdf::ElementPtr)

Function pointer to create a certain thruster dynamics object.

Definition at line 57 of file Dynamics.hh.

typedef HydrodynamicModel*(* gazebo::HydrodynamicModelCreator) (sdf::ElementPtr, physics::LinkPtr)

Function pointer to create a certain a model.

Definition at line 110 of file HydrodynamicModel.hh.

typedef boost::shared_ptr<HydrodynamicModel> gazebo::HydrodynamicModelPtr

Pointer to model.

Definition at line 107 of file HydrodynamicModel.hh.

typedef LiftDrag*(* gazebo::LiftDragCreator) (sdf::ElementPtr)

Function pointer to create a certain LiftDrag object.

Definition at line 66 of file LiftDragModel.hh.

typedef UmbilicalModel*(* gazebo::UmbilicalModelCreator) (sdf::ElementPtr, physics::ModelPtr)

Function pointer to create a certain conversion function.

Definition at line 55 of file UmbilicalModel.hh.

typedef boost::shared_ptr<UmbilicalSegment> gazebo::UmbilicalSegmentPtr

Definition at line 58 of file UmbilicalPlugin.hh.

Function Documentation

Eigen::Matrix3d gazebo::CrossProductOperator ( Eigen::Vector3d  _x)
inline

Returns the cross product operator matrix for Eigen vectors.

Definition at line 67 of file Def.hh.

Eigen::Matrix3d gazebo::CrossProductOperator ( ignition::math::Vector3d  _x)
inline

Returns the cross product operator matrix for Gazebo vectors.

Definition at line 76 of file Def.hh.

Eigen::Vector6d gazebo::EigenStack ( const ignition::math::Vector3d &  _x,
const ignition::math::Vector3d &  _y 
)
inline

Definition at line 97 of file Def.hh.

gazebo::GZ_REGISTER_MODEL_PLUGIN ( UmbilicalPlugin  )
ignition::math::Matrix3d gazebo::Mat3dToGazebo ( const Eigen::Matrix3d &  _x)
inline

Definition at line 112 of file Def.hh.

gazebo::REGISTER_CONVERSIONFUNCTION_CREATOR ( ConversionFunctionBasic  ,
&ConversionFunctionBasic::create   
)

Definition at line 70 of file ThrusterConversionFcn.cc.

gazebo::REGISTER_CONVERSIONFUNCTION_CREATOR ( ConversionFunctionBessa  ,
&ConversionFunctionBessa::create   
)

Definition at line 118 of file ThrusterConversionFcn.cc.

gazebo::REGISTER_CONVERSIONFUNCTION_CREATOR ( ConversionFunctionLinearInterp  ,
&ConversionFunctionLinearInterp::create   
)

Definition at line 225 of file ThrusterConversionFcn.cc.

gazebo::REGISTER_DYNAMICS_CREATOR ( DynamicsZeroOrder  ,
&DynamicsZeroOrder::create   
)

Definition at line 75 of file Dynamics.cc.

gazebo::REGISTER_DYNAMICS_CREATOR ( DynamicsFirstOrder  ,
&DynamicsFirstOrder::create   
)

Definition at line 92 of file Dynamics.cc.

gazebo::REGISTER_DYNAMICS_CREATOR ( ThrusterDynamicsYoerger  ,
&ThrusterDynamicsYoerger::create   
)

Definition at line 135 of file Dynamics.cc.

gazebo::REGISTER_DYNAMICS_CREATOR ( ThrusterDynamicsBessa  ,
&ThrusterDynamicsBessa::create   
)

Definition at line 184 of file Dynamics.cc.

gazebo::REGISTER_HYDRODYNAMICMODEL_CREATOR ( HMFossen  ,
&HMFossen::create   
)
gazebo::REGISTER_HYDRODYNAMICMODEL_CREATOR ( HMSphere  ,
&HMSphere::create   
)
gazebo::REGISTER_HYDRODYNAMICMODEL_CREATOR ( HMCylinder  ,
&HMCylinder::create   
)
gazebo::REGISTER_HYDRODYNAMICMODEL_CREATOR ( HMSpheroid  ,
&HMSpheroid::create   
)
gazebo::REGISTER_HYDRODYNAMICMODEL_CREATOR ( HMBox  ,
&HMBox::create   
)
gazebo::REGISTER_LIFTDRAG_CREATOR ( LiftDragQuadratic  ,
&LiftDragQuadratic::create   
)

Definition at line 82 of file LiftDragModel.cc.

gazebo::REGISTER_LIFTDRAG_CREATOR ( LiftDragTwoLines  ,
&LiftDragTwoLines::create   
)

Definition at line 168 of file LiftDragModel.cc.

std::vector<double> gazebo::Str2Vector ( std::string  _input)
inline

Conversion of a string to a double vector.

Definition at line 55 of file Def.hh.

Eigen::Vector3d gazebo::ToEigen ( const ignition::math::Vector3d &  _x)
inline

Definition at line 83 of file Def.hh.

Eigen::Matrix3d gazebo::ToEigen ( const ignition::math::Matrix3d &  _x)
inline

Definition at line 88 of file Def.hh.

ignition::math::Vector3d gazebo::Vec3dToGazebo ( const Eigen::Vector3d &  _x)
inline

Definition at line 107 of file Def.hh.



uuv_gazebo_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Thu Jun 18 2020 03:28:24