Namespaces | Classes | Typedefs | Functions | Variables
gazebo Namespace Reference

Namespaces

 sensors
 

Classes

class  BuoyantObject
 
class  ConversionFunction
 
class  ConversionFunctionBasic
 
class  ConversionFunctionBessa
 
class  ConversionFunctionFactory
 
class  ConversionFunctionLinearInterp
 
class  CPCROSPlugin
 
class  DVLROSPlugin
 TODO: Modify computation of velocity using the beams. More...
 
class  Dynamics
 
class  DynamicsFactory
 
class  DynamicsFirstOrder
 
class  DynamicsZeroOrder
 
class  FinPlugin
 
class  GazeboRos
 
class  GazeboRosBlockLaser
 
class  GazeboRosBumper
 
class  GazeboRosCamera
 
class  GazeboRosCameraUtils
 
class  GazeboRosDepthCamera
 
class  GazeboRosDiffDrive
 
class  GazeboRosElevator
 
class  GazeboRosF3D
 
class  GazeboRosForce
 
class  GazeboRosFT
 
class  GazeboRosHandOfGod
 
class  GazeboRosHarness
 
class  GazeboRosImageSonar
 
class  GazeboRosIMU
 
class  GazeboRosImuSensor
 
class  GazeboRosJointPoseTrajectory
 
class  GazeboRosJointStatePublisher
 
class  GazeboRosJointTrajectory
 
class  GazeboRosLaser
 
class  GazeboRosMultiCamera
 
class  GazeboRosOpenniKinect
 
class  GazeboRosP3D
 
class  GazeboRosPlanarMove
 
class  GazeboRosProjector
 
class  GazeboRosProsilica
 
class  GazeboRosRange
 
class  GazeboRosSkidSteerDrive
 
class  GazeboRosTemplate
 
class  GazeboRosTricycleDrive
 
class  GazeboRosTriggeredCamera
 
class  GazeboRosTriggeredMultiCamera
 
class  GazeboRosVacuumGripper
 
class  GazeboRosVideo
 
class  GPSROSPlugin
 
class  HMBox
 
class  HMCylinder
 
class  HMFossen
 
class  HMSphere
 
class  HMSpheroid
 
class  HydrodynamicModel
 
class  HydrodynamicModelFactory
 
struct  IMUParameters
 IMUParameters stores all IMU model parameters. A description of these parameters can be found here: https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model-and-Intrinsics. More...
 
class  IMUROSPlugin
 
class  LiftDrag
 
class  LiftDragFactory
 
class  LiftDragQuadratic
 
class  LiftDragTwoLines
 
struct  MagnetometerParameters
 
class  MagnetometerROSPlugin
 
class  MultiCameraPlugin
 
class  PoseGTROSPlugin
 
class  ROSBaseModelPlugin
 
class  ROSBasePlugin
 
class  ROSBaseSensorPlugin
 
class  RPTROSPlugin
 
class  SubseaPressureROSPlugin
 
class  ThrusterDynamicsBessa
 
class  ThrusterDynamicsYoerger
 
class  ThrusterPlugin
 
class  UmbilicalModel
 
class  UmbilicalModelBerg
 
class  UmbilicalModelFactory
 
class  UmbilicalPlugin
 
class  UmbilicalSegment
 
class  UnderwaterCameraROSPlugin
 
class  UnderwaterObjectPlugin
 
class  VideoVisual
 

Typedefs

typedef const boost::shared_ptr< const uuv_gazebo_plugins_msgs::msgs::Double > ConstDoublePtr
 
typedef ConversionFunction *(* ConversionFunctionCreator) (sdf::ElementPtr)
 
typedef Dynamics *(* DynamicsCreator) (sdf::ElementPtr)
 
typedef boost::shared_ptr< GazeboRosGazeboRosPtr
 
typedef HydrodynamicModel *(* HydrodynamicModelCreator) (sdf::ElementPtr, physics::LinkPtr)
 
typedef boost::shared_ptr< HydrodynamicModelHydrodynamicModelPtr
 
typedef LiftDrag *(* LiftDragCreator) (sdf::ElementPtr)
 
typedef std::map< std::string, Ogre::Pass * > OgrePassMap
 
typedef OgrePassMap::iterator OgrePassMapIterator
 
typedef UmbilicalModel *(* UmbilicalModelCreator) (sdf::ElementPtr, physics::ModelPtr)
 
typedef boost::shared_ptr< UmbilicalSegmentUmbilicalSegmentPtr
 

Functions

Eigen::Matrix3d CrossProductOperator (Eigen::Vector3d _x)
 
Eigen::Matrix3d CrossProductOperator (ignition::math::Vector3d _x)
 
Eigen::Vector6d EigenStack (const ignition::math::Vector3d &_x, const ignition::math::Vector3d &_y)
 
std::string GetModelName (const sensors::SensorPtr &parent)
 
std::string GetRobotNamespace (const sensors::SensorPtr &parent, const sdf::ElementPtr &sdf, const char *pInfo=NULL)
 
template<class T >
bool GetSDFParam (sdf::ElementPtr sdf, const std::string &name, T &param, const T &default_value, const bool &verbose=false)
 Obtains a parameter from sdf. More...
 
 GZ_REGISTER_MODEL_PLUGIN (GazeboRosFT)
 
 GZ_REGISTER_MODEL_PLUGIN (GazeboRosJointPoseTrajectory)
 
 GZ_REGISTER_MODEL_PLUGIN (UmbilicalPlugin)
 
 GZ_REGISTER_MODEL_PLUGIN (GazeboRosVacuumGripper)
 
 GZ_REGISTER_MODEL_PLUGIN (GazeboRosF3D)
 
 GZ_REGISTER_MODEL_PLUGIN (GazeboRosProjector)
 
 GZ_REGISTER_MODEL_PLUGIN (GazeboRosTemplate)
 
 GZ_REGISTER_MODEL_PLUGIN (GazeboRosForce)
 
 GZ_REGISTER_MODEL_PLUGIN (GazeboRosHandOfGod)
 
 GZ_REGISTER_MODEL_PLUGIN (GazeboRosJointTrajectory)
 
 GZ_REGISTER_MODEL_PLUGIN (GazeboRosP3D)
 
 GZ_REGISTER_VISUAL_PLUGIN (GazeboRosVideo)
 
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 (ThrusterDynamicsYoerger,&ThrusterDynamicsYoerger::create) Dynamics *ThrusterDynamicsYoerger
 
 REGISTER_DYNAMICS_CREATOR (ThrusterDynamicsBessa,&ThrusterDynamicsBessa::create) Dynamics *ThrusterDynamicsBessa
 
 REGISTER_DYNAMICS_CREATOR (DynamicsFirstOrder,&DynamicsFirstOrder::create) Dynamics *DynamicsFirstOrder
 
 REGISTER_HYDRODYNAMICMODEL_CREATOR (HMFossen,&HMFossen::create)
 
 REGISTER_HYDRODYNAMICMODEL_CREATOR (HMBox,&HMBox::create)
 
 REGISTER_HYDRODYNAMICMODEL_CREATOR (HMSpheroid,&HMSpheroid::create)
 
 REGISTER_HYDRODYNAMICMODEL_CREATOR (HMCylinder,&HMCylinder::create)
 
 REGISTER_HYDRODYNAMICMODEL_CREATOR (HMSphere,&HMSphere::create)
 
 REGISTER_LIFTDRAG_CREATOR (LiftDragTwoLines,&LiftDragTwoLines::create) LiftDrag *LiftDragTwoLines
 
 REGISTER_LIFTDRAG_CREATOR (LiftDragQuadratic,&LiftDragQuadratic::create) LiftDrag *LiftDragQuadratic
 
std::vector< double > Str2Vector (std::string _input)
 
Eigen::Matrix3d ToEigen (const ignition::math::Matrix3d &_x)
 
Eigen::Vector3d ToEigen (const ignition::math::Vector3d &_x)
 
ignition::math::Vector3d Vec3dToGazebo (const Eigen::Vector3d &_x)
 

Variables

 LEFT
 
 LEFT
 
 LEFT_FRONT
 
 LEFT_REAR
 
 RIGHT
 
 RIGHT
 
 RIGHT_FRONT
 
 RIGHT_REAR
 

Function Documentation

template<class T >
bool gazebo::GetSDFParam ( sdf::ElementPtr  sdf,
const std::string &  name,
T &  param,
const T &  default_value,
const bool &  verbose = false 
)

Obtains a parameter from sdf.

Parameters
[in]sdfPointer to the sdf object.
[in]nameName of the parameter.
[out]paramParam Variable to write the parameter to.
[in]default_valueDefault value, if the parameter not available.
[in]verboseIf true, gzerror if the parameter is not available.

Definition at line 47 of file Common.hh.



uuv_sensor_ros_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Mon Jul 1 2019 19:39:20