Protected Member Functions | Static Protected Member Functions | Protected Attributes | List of all members
gazebo::ServerFixture Class Reference

#include <ServerFixture.hh>

Inheritance diagram for gazebo::ServerFixture:
Inheritance graph
[legend]

Protected Member Functions

 ServerFixture ()
 Constructor. More...
 
virtual ~ServerFixture ()
 Destructor. More...
 
void DoubleCompare (double *_scanA, double *_scanB, unsigned int _sampleCount, double &_diffMax, double &_diffSum, double &_diffAvg)
 Function to compare two double arrays (for example two laser scans). More...
 
void FloatCompare (float *_scanA, float *_scanB, unsigned int _sampleCount, float &_diffMax, float &_diffSum, float &_diffAvg)
 Function to compare two float arrays (for example two laser scans). More...
 
math::Pose GetEntityPose (const std::string &_name)
 Get the pose of an entity. More...
 
void GetFrame (const std::string &_cameraName, unsigned char **_imgData, unsigned int &_width, unsigned int &_height)
 Get an image frame from a camera. More...
 
void GetMemInfo (double &_resident, double &_share)
 Get the current memory information. More...
 
physics::ModelPtr GetModel (const std::string &_name)
 Get a pointer to a model. More...
 
double GetPercentRealTime () const
 Get the real-time factor. More...
 
rendering::ScenePtr GetScene (const std::string &_sceneName="default")
 Get a pointer to the rendering scene. More...
 
std::string GetUniqueString (const std::string &_prefix)
 Get unique string with a specified prefix. More...
 
bool HasEntity (const std::string &_name)
 Return true if the named entity exists. More...
 
void ImageCompare (unsigned char *_imageA, unsigned char *_imageB, unsigned int _width, unsigned int _height, unsigned int _depth, unsigned int &_diffMax, unsigned int &_diffSum, double &_diffAvg)
 Function to compare two images. More...
 
virtual void Load (const std::string &_worldFilename)
 Load a world based on a filename. More...
 
virtual void Load (const std::string &_worldFilename, bool _paused)
 Load a world based on a filename and set simulation paused/un-paused. More...
 
virtual void Load (const std::string &_worldFilename, bool _paused, const std::string &_physics, const std::vector< std::string > &_systemPlugins={})
 Load a world based on a filename and set simulation paused/un-paused, and specify physics engine. More...
 
void LoadPlugin (const std::string &_filename, const std::string &_name)
 Load a plugin. More...
 
void OnPose (ConstPosesStampedPtr &_msg)
 Function that received poses messages from a running simulation. More...
 
void OnStats (ConstWorldStatisticsPtr &_msg)
 Function that received world stastics messages. More...
 
void PrintImage (const std::string &_name, unsigned char **_image, unsigned int _width, unsigned int _height, unsigned int _depth)
 Print image data to screen. More...
 
void PrintScan (const std::string &_name, double *_scan, unsigned int _sampleCount)
 Print laser scan to screen. More...
 
void Record (const std::string &_name, const double _data)
 Helper to record data to gtest xml output. More...
 
void Record (const std::string &_prefix, const math::SignalStats &_stats)
 Helper to record signal statistics to gtest xml output. More...
 
void Record (const std::string &_prefix, const math::Vector3Stats &_stats)
 Helper to record Vector3 signal statistics to gtest xml output. More...
 
void RemoveModel (const std::string &_name)
 Remove a model by name. More...
 
void RemovePlugin (const std::string &_name)
 Remove a plugin. More...
 
void RunServer (const std::string &_worldFilename)
 Run the server. More...
 
void RunServer (const std::string &_worldFilename, bool _paused, const std::string &_physics, const std::vector< std::string > &_systemPlugins={})
 Run the server, start paused/unpaused, and specify the physics engine. More...
 
void SetPause (bool _pause)
 Set a running simulation paused/unpaused. More...
 
void SpawnBox (const std::string &_name, const math::Vector3 &_size, const math::Vector3 &_pos, const math::Vector3 &_rpy, bool _static=false)
 Spawn a box. More...
 
void SpawnCamera (const std::string &_modelName, const std::string &_cameraName, const math::Vector3 &_pos, const math::Vector3 &_rpy, unsigned int _width=320, unsigned int _height=240, double _rate=25, const std::string &_noiseType="", double _noiseMean=0.0, double _noiseStdDev=0.0, bool _distortion=false, double _distortionK1=0.0, double _distortionK2=0.0, double _distortionK3=0.0, double _distortionP1=0.0, double _distortionP2=0.0, double _cx=0.5, double _cy=0.5)
 Spawn a camera. More...
 
void SpawnCylinder (const std::string &_name, const math::Vector3 &_pos, const math::Vector3 &_rpy, bool _static=false)
 Spawn a cylinder. More...
 
void SpawnEmptyLink (const std::string &_name, const math::Vector3 &_pos, const math::Vector3 &_rpy, bool _static=false)
 Spawn an empty link. More...
 
void SpawnGpuRaySensor (const std::string &_modelName, const std::string &_raySensorName, const math::Vector3 &_pos, const math::Vector3 &_rpy, double _hMinAngle=-2.0, double _hMaxAngle=2.0, double _minRange=0.08, double _maxRange=10, double _rangeResolution=0.01, unsigned int _samples=640, const std::string &_noiseType="", double _noiseMean=0.0, double _noiseStdDev=0.0)
 Spawn a gpu laser. More...
 
void SpawnImuSensor (const std::string &_modelName, const std::string &_imuSensorName, const math::Vector3 &_pos, const math::Vector3 &_rpy, const std::string &_noiseType="", double _rateNoiseMean=0.0, double _rateNoiseStdDev=0.0, double _rateBiasMean=0.0, double _rateBiasStdDev=0.0, double _accelNoiseMean=0.0, double _accelNoiseStdDev=0.0, double _accelBiasMean=0.0, double _accelBiasStdDev=0.0)
 Spawn an imu sensor laser. More...
 
void SpawnLight (const std::string &_name, const std::string &_type, const math::Vector3 &_pos, const math::Vector3 &_rpy, const common::Color &_diffuse=common::Color::White, const common::Color &_specular=common::Color::White, const math::Vector3 &_direction=-math::Vector3::UnitZ, double _attenuationRange=20, double _attenuationConstant=0.5, double _attenuationLinear=0.01, double _attenuationQuadratic=0.001, double _spotInnerAngle=0, double _spotOuterAngle=0, double _spotFallOff=0, bool _castShadows=true)
 Spawn a light. More...
 
physics::ModelPtr SpawnModel (const msgs::Model &_msg)
 Spawn a model from a msgs::Model and return ModelPtr. More...
 
void SpawnModel (const std::string &_filename)
 Spawn a model from file. More...
 
void SpawnRaySensor (const std::string &_modelName, const std::string &_raySensorName, const math::Vector3 &_pos, const math::Vector3 &_rpy, double _hMinAngle=-2.0, double _hMaxAngle=2.0, double _vMinAngle=-1.0, double _vMaxAngle=1.0, double _minRange=0.08, double _maxRange=10, double _rangeResolution=0.01, unsigned int _samples=640, unsigned int _vSamples=1, double _hResolution=1.0, double _vResolution=1.0, const std::string &_noiseType="", double _noiseMean=0.0, double _noiseStdDev=0.0)
 Spawn a laser. More...
 
void SpawnSDF (const std::string &_sdf)
 Send a factory message based on an SDF string. More...
 
void SpawnSphere (const std::string &_name, const math::Vector3 &_pos, const math::Vector3 &_rpy, bool _wait=true, bool _static=false)
 Spawn a sphere. More...
 
void SpawnSphere (const std::string &_name, const math::Vector3 &_pos, const math::Vector3 &_rpy, const math::Vector3 &_cog, double _radius, bool _wait=true, bool _static=false)
 Spawn a sphere. More...
 
void SpawnTrimesh (const std::string &_name, const std::string &_modelPath, const math::Vector3 &_scale, const math::Vector3 &_pos, const math::Vector3 &_rpy, bool _static=false)
 Spawn a triangle mesh. More...
 
void SpawnUnitAltimeterSensor (const std::string &_name, const std::string &_sensorName, const std::string &_collisionType, const std::string &_topic, const ignition::math::Vector3d &_pos, const ignition::math::Vector3d &_rpy, bool _static=false)
 Spawn an altimeter sensor on a link. More...
 
void SpawnUnitContactSensor (const std::string &_name, const std::string &_sensorName, const std::string &_collisionType, const math::Vector3 &_pos, const math::Vector3 &_rpy, bool _static=false)
 Spawn a contact sensor with the specified collision geometry. More...
 
void SpawnUnitImuSensor (const std::string &_name, const std::string &_sensorName, const std::string &_collisionType, const std::string &_topic, const math::Vector3 &_pos, const math::Vector3 &_rpy, bool _static=false)
 Spawn an IMU sensor on a link. More...
 
void SpawnUnitMagnetometerSensor (const std::string &_name, const std::string &_sensorName, const std::string &_collisionType, const std::string &_topic, const ignition::math::Vector3d &_pos, const ignition::math::Vector3d &_rpy, bool _static=false)
 Spawn a magnetometer sensor on a link. More...
 
void SpawnWirelessReceiverSensor (const std::string &_name, const std::string &_sensorName, const math::Vector3 &_pos, const math::Vector3 &_rpy, double _minFreq, double _maxFreq, double _power, double _gain, double _sensitivity, bool _visualize=true)
 Spawn an Wireless receiver sensor on a link. More...
 
void SpawnWirelessTransmitterSensor (const std::string &_name, const std::string &_sensorName, const math::Vector3 &_pos, const math::Vector3 &_rpy, const std::string &_essid, double _freq, double _power, double _gain, bool _visualize=true)
 Spawn an Wireless transmitter sensor on a link. More...
 
virtual void TearDown ()
 Tear down the test fixture. This gets called by gtest. More...
 
virtual void Unload ()
 Unload the test fixture. More...
 
void WaitUntilEntitySpawn (const std::string &_name, unsigned int _sleepEach, int _retries)
 Wait for a number of ms. More...
 
void WaitUntilSensorSpawn (const std::string &_name, unsigned int _sleepEach, int _retries)
 Wait for a number of ms. More...
 

Static Protected Member Functions

template<typename T >
static void CheckPointer (boost::shared_ptr< T > _ptr)
 Check that a pointer is not NULL. More...
 

Protected Attributes

transport::PublisherPtr factoryPub
 Factory publisher. More...
 
transport::NodePtr node
 Pointer to a node for communication. More...
 
common::Time pauseTime
 
std::map< std::string, math::Poseposes
 Map of received poses. More...
 
transport::SubscriberPtr poseSub
 Pose subscription. More...
 
common::Time realTime
 
boost::mutex receiveMutex
 Mutex to protect data structures that store messages. More...
 
transport::PublisherPtr requestPub
 Request publisher. More...
 
Serverserver
 Pointer the Gazebo server. More...
 
boost::thread * serverThread
 Pointer the thread the runs the server. More...
 
common::Time simTime
 Current simulation time, real time, and pause time. More...
 
transport::SubscriberPtr statsSub
 World statistics subscription. More...
 

Constructor & Destructor Documentation

gazebo::ServerFixture::ServerFixture ( )
protected

Constructor.

virtual gazebo::ServerFixture::~ServerFixture ( )
protectedvirtual

Destructor.

Member Function Documentation

template<typename T >
static void gazebo::ServerFixture::CheckPointer ( boost::shared_ptr< T >  _ptr)
inlinestaticprotected

Check that a pointer is not NULL.

A function is created for this purpose, since ASSERT's cannot be called from non-void functions.

Parameters
[in]_ptrPointer to verify is not NULL.

References NULL.

void gazebo::ServerFixture::DoubleCompare ( double *  _scanA,
double *  _scanB,
unsigned int  _sampleCount,
double &  _diffMax,
double &  _diffSum,
double &  _diffAvg 
)
protected

Function to compare two double arrays (for example two laser scans).

Parameters
[in]_scanAFirst double array.
[in]_scanBSecond double array.
[in]_sampleCountNumber of samples in each double array.
[out]_diffMaxMaximum difference between the two arrays.
[out]_diffSumSum of the differences between the two arrays.
[out]_diffAvgAverage difference between the two arrays.
void gazebo::ServerFixture::FloatCompare ( float *  _scanA,
float *  _scanB,
unsigned int  _sampleCount,
float &  _diffMax,
float &  _diffSum,
float &  _diffAvg 
)
protected

Function to compare two float arrays (for example two laser scans).

Parameters
[in]_scanAFirst float array.
[in]_scanBSecond float array.
[in]_sampleCountNumber of samples in each float array.
[out]_diffMaxMaximum difference between the two arrays.
[out]_diffSumSum of the differences between the two arrays.
[out]_diffAvgAverage difference between the two arrays.
math::Pose gazebo::ServerFixture::GetEntityPose ( const std::string &  _name)
protected

Get the pose of an entity.

Parameters
[in]_nameName of the entity.
Returns
Pose of the named entity.
void gazebo::ServerFixture::GetFrame ( const std::string &  _cameraName,
unsigned char **  _imgData,
unsigned int &  _width,
unsigned int &  _height 
)
protected

Get an image frame from a camera.

Parameters
[in]_cameraNameName of the camera to get a frame from.
[out]_imgDataArray that receives the image data.
[in]_widthWidth of the image frame.
[in]_heightHeight of the image frame.
void gazebo::ServerFixture::GetMemInfo ( double &  _resident,
double &  _share 
)
protected

Get the current memory information.

Parameters
[out]_residentResident memory.
[out]_shareShared memory.
physics::ModelPtr gazebo::ServerFixture::GetModel ( const std::string &  _name)
protected

Get a pointer to a model.

Parameters
[in]_nameName of the model to get.
Returns
Pointer to the model, or NULL if the model was not found.
double gazebo::ServerFixture::GetPercentRealTime ( ) const
protected

Get the real-time factor.

Returns
The percent real time simulation is running.
rendering::ScenePtr gazebo::ServerFixture::GetScene ( const std::string &  _sceneName = "default")
protected

Get a pointer to the rendering scene.

Parameters
[in]_sceneNameName of the scene to get.
std::string gazebo::ServerFixture::GetUniqueString ( const std::string &  _prefix)
protected

Get unique string with a specified prefix.

Parameters
[in]_prefixPrefix for unique string.
Returns
String with prefix and unique number as suffix.
bool gazebo::ServerFixture::HasEntity ( const std::string &  _name)
protected

Return true if the named entity exists.

Parameters
[in]_nameName of the entity to check for.
Returns
True if the entity exists.
void gazebo::ServerFixture::ImageCompare ( unsigned char *  _imageA,
unsigned char *  _imageB,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth,
unsigned int &  _diffMax,
unsigned int &  _diffSum,
double &  _diffAvg 
)
protected

Function to compare two images.

Parameters
[in]_imageAFirst image to compare.
[in]_imageBSecond image to compare.
[in]_widthWidth of both images.
[in]_heightHeight of both images.
[in]_depthDepth of both images.
[out]_diffMaxMaximum difference between the two arrays.
[out]_diffSumSum of the differences between the two arrays.
[out]_diffAvgAverage difference between the two arrays.
virtual void gazebo::ServerFixture::Load ( const std::string &  _worldFilename)
protectedvirtual

Load a world based on a filename.

Parameters
[in]_worldFilenameName of the world to load.
virtual void gazebo::ServerFixture::Load ( const std::string &  _worldFilename,
bool  _paused 
)
protectedvirtual

Load a world based on a filename and set simulation paused/un-paused.

Parameters
[in]_worldFilenameName of the world to load.
[in]_pausedTrue to start the world paused.
virtual void gazebo::ServerFixture::Load ( const std::string &  _worldFilename,
bool  _paused,
const std::string &  _physics,
const std::vector< std::string > &  _systemPlugins = {} 
)
protectedvirtual

Load a world based on a filename and set simulation paused/un-paused, and specify physics engine.

This versions allows plugins to be loaded (via the cmd line args)

Parameters
[in]_worldFilenameName of the world to load.
[in]_pausedTrue to start the world paused.
[in]_physicsName of the physics engine.
[in]_systemPluginsArray of system plugins to load.
void gazebo::ServerFixture::LoadPlugin ( const std::string &  _filename,
const std::string &  _name 
)
protected

Load a plugin.

Parameters
[in]_filenamePlugin filename to load.
[in]_nameName to associate with with the plugin.
void gazebo::ServerFixture::OnPose ( ConstPosesStampedPtr &  _msg)
protected

Function that received poses messages from a running simulation.

Parameters
[in]_msgPose message.
void gazebo::ServerFixture::OnStats ( ConstWorldStatisticsPtr &  _msg)
protected

Function that received world stastics messages.

Parameters
[in]_msgWorld statistics message.
void gazebo::ServerFixture::PrintImage ( const std::string &  _name,
unsigned char **  _image,
unsigned int  _width,
unsigned int  _height,
unsigned int  _depth 
)
protected

Print image data to screen.

This is used to generate test data.

Parameters
[in]_nameName to associate with the printed data.
[in]_imageThe raw image data.
[in]_widthWidth of the image.
[in]_heightHeight of the image.
[in]_depthPixel depth.
void gazebo::ServerFixture::PrintScan ( const std::string &  _name,
double *  _scan,
unsigned int  _sampleCount 
)
protected

Print laser scan to screen.

This is used to generate test data.

Parameters
[in]_nameName to associate with the printed data.
[in]_scanThe laser scan data.
[in]_sampleCountNumber of samples in the scan data.
void gazebo::ServerFixture::Record ( const std::string &  _name,
const double  _data 
)
protected

Helper to record data to gtest xml output.

Parameters
[in]_nameName of data.
[in]_dataFloating point number to store.
void gazebo::ServerFixture::Record ( const std::string &  _prefix,
const math::SignalStats _stats 
)
protected

Helper to record signal statistics to gtest xml output.

Parameters
[in]_prefixPrefix string for data names.
[in]_statsSignal statistics to store.
void gazebo::ServerFixture::Record ( const std::string &  _prefix,
const math::Vector3Stats _stats 
)
protected

Helper to record Vector3 signal statistics to gtest xml output.

Parameters
[in]_prefixPrefix string for data names.
[in]_statsVector3 signal statistics to store.
void gazebo::ServerFixture::RemoveModel ( const std::string &  _name)
protected

Remove a model by name.

Parameters
[in]_nameName of the model to remove.
void gazebo::ServerFixture::RemovePlugin ( const std::string &  _name)
protected

Remove a plugin.

Parameters
[in]_nameName of the plugin to remove.
void gazebo::ServerFixture::RunServer ( const std::string &  _worldFilename)
protected

Run the server.

Parameters
[in]_worldFilenameName of the world to run in simulation.
void gazebo::ServerFixture::RunServer ( const std::string &  _worldFilename,
bool  _paused,
const std::string &  _physics,
const std::vector< std::string > &  _systemPlugins = {} 
)
protected

Run the server, start paused/unpaused, and specify the physics engine.

Parameters
[in]_worldFilenameName of the world to load.
[in]_pausedTrue to start the world paused.
[in]_physicsName of the physics engine.
[in]_systemPluginsArray of system plugins to load.
void gazebo::ServerFixture::SetPause ( bool  _pause)
protected

Set a running simulation paused/unpaused.

void gazebo::ServerFixture::SpawnBox ( const std::string &  _name,
const math::Vector3 _size,
const math::Vector3 _pos,
const math::Vector3 _rpy,
bool  _static = false 
)
protected

Spawn a box.

Parameters
[in]_nameName for the model.
[in]_sizeSize of the box.
[in]_posPosition for the model.
[in]_rpyRoll, pitch, yaw for the model.
[in]_staticTrue to make the model static.
void gazebo::ServerFixture::SpawnCamera ( const std::string &  _modelName,
const std::string &  _cameraName,
const math::Vector3 _pos,
const math::Vector3 _rpy,
unsigned int  _width = 320,
unsigned int  _height = 240,
double  _rate = 25,
const std::string &  _noiseType = "",
double  _noiseMean = 0.0,
double  _noiseStdDev = 0.0,
bool  _distortion = false,
double  _distortionK1 = 0.0,
double  _distortionK2 = 0.0,
double  _distortionK3 = 0.0,
double  _distortionP1 = 0.0,
double  _distortionP2 = 0.0,
double  _cx = 0.5,
double  _cy = 0.5 
)
protected

Spawn a camera.

Parameters
[in]_modelNameName of the model.
[in]_cameraNameName of the camera.
[in]_posCamera position.
[in]_rpyCamera roll, pitch, yaw.
[in]_widthOutput image width.
[in]_heightOutput image height.
[in]_rateOutput Hz.
[in]_noiseTypeType of noise to apply.
[in]_noiseMeanMean noise value.
[in]_noiseStdDevStandard deviation of the noise.
[in]_distortionK1Distortion coefficient k1.
[in]_distortionK2Distortion coefficient k2.
[in]_distortionK3Distortion coefficient k3.
[in]_distortionP1Distortion coefficient P1.
[in]_distortionP2Distortion coefficient p2.
[in]_cxNormalized optical center x, used for distortion.
[in]_cyNormalized optical center y, used for distortion.
void gazebo::ServerFixture::SpawnCylinder ( const std::string &  _name,
const math::Vector3 _pos,
const math::Vector3 _rpy,
bool  _static = false 
)
protected

Spawn a cylinder.

Parameters
[in]_nameName for the model.
[in]_posPosition for the model.
[in]_rpyRoll, pitch, yaw for the model.
[in]_staticTrue to make the model static.
void gazebo::ServerFixture::SpawnEmptyLink ( const std::string &  _name,
const math::Vector3 _pos,
const math::Vector3 _rpy,
bool  _static = false 
)
protected

Spawn an empty link.

Parameters
[in]_nameName for the model.
[in]_posPosition for the model.
[in]_rpyRoll, pitch, yaw for the model.
[in]_staticTrue to make the model static.
void gazebo::ServerFixture::SpawnGpuRaySensor ( const std::string &  _modelName,
const std::string &  _raySensorName,
const math::Vector3 _pos,
const math::Vector3 _rpy,
double  _hMinAngle = -2.0,
double  _hMaxAngle = 2.0,
double  _minRange = 0.08,
double  _maxRange = 10,
double  _rangeResolution = 0.01,
unsigned int  _samples = 640,
const std::string &  _noiseType = "",
double  _noiseMean = 0.0,
double  _noiseStdDev = 0.0 
)
protected

Spawn a gpu laser.

Parameters
[in]_modelNameName of the model.
[in]_raySensorNameName of the laser.
[in]_posCamera position.
[in]_rpyCamera roll, pitch, yaw.
[in]_hMinAngleHorizontal min angle
[in]_hMaxAngleHorizontal max angle
[in]_minRangeMin range
[in]_maxRangeMax range
[in]_rangeResolutionResolution of the scan
[in]_samplesNumber of samples.
[in]_rateOutput Hz.
[in]_noiseTypeType of noise to apply.
[in]_noiseMeanMean noise value.
[in]_noiseStdDevStandard deviation of the noise.
void gazebo::ServerFixture::SpawnImuSensor ( const std::string &  _modelName,
const std::string &  _imuSensorName,
const math::Vector3 _pos,
const math::Vector3 _rpy,
const std::string &  _noiseType = "",
double  _rateNoiseMean = 0.0,
double  _rateNoiseStdDev = 0.0,
double  _rateBiasMean = 0.0,
double  _rateBiasStdDev = 0.0,
double  _accelNoiseMean = 0.0,
double  _accelNoiseStdDev = 0.0,
double  _accelBiasMean = 0.0,
double  _accelBiasStdDev = 0.0 
)
protected

Spawn an imu sensor laser.

Parameters
[in]_modelNameName of the model.
[in]_imuSensorNameName of the imu sensor.
[in]_posCamera position.
[in]_rpyCamera roll, pitch, yaw.
[in]_noiseTypeType of noise to apply.
[in]_noiseMeanMean noise value.
[in]_noiseStdDevStandard deviation of the noise.
[in]_accelNoiseMeanAcceleration based noise mean.
[in]_accelNoiseStdDevAcceleration based noise standard deviation.
[in]_accelBiasMeanAcceleration mean bias
[in]_accelBiasStdDevAcceleration standard deviation bias
void gazebo::ServerFixture::SpawnLight ( const std::string &  _name,
const std::string &  _type,
const math::Vector3 _pos,
const math::Vector3 _rpy,
const common::Color _diffuse = common::Color::White,
const common::Color _specular = common::Color::White,
const math::Vector3 _direction = -math::Vector3::UnitZ,
double  _attenuationRange = 20,
double  _attenuationConstant = 0.5,
double  _attenuationLinear = 0.01,
double  _attenuationQuadratic = 0.001,
double  _spotInnerAngle = 0,
double  _spotOuterAngle = 0,
double  _spotFallOff = 0,
bool  _castShadows = true 
)
protected

Spawn a light.

Parameters
[in]_nameName for the light.
[in]_sizeType of light - "spot", "directional", or "point".
[in]_posPosition for the light.
[in]_rpyRoll, pitch, yaw for the light.
[in]_diffuseDiffuse color of the light.
[in]_specularSpecular color of the light.
[in]_directionDirection of the light ("spot" and "directional").
[in]_attenuationRangeRange of attenuation.
[in]_attenuationConstantConstant component of attenuation
[in]_attenuationLinearLinear component of attenuation
[in]_attenuationQuadraticQuadratic component of attenuation
[in]_spotInnerAngleInner angle ("spot" only).
[in]_spotOuterAngleOuter angle ("spot" only).
[in]_spotFallOffFall off ("spot" only).
[in]_castShadowsTrue to cast shadows.
physics::ModelPtr gazebo::ServerFixture::SpawnModel ( const msgs::Model &  _msg)
protected

Spawn a model from a msgs::Model and return ModelPtr.

Parameters
[in]_msgModel message.
Returns
Pointer to model.
void gazebo::ServerFixture::SpawnModel ( const std::string &  _filename)
protected

Spawn a model from file.

Parameters
[in]_filenameFile to load a model from.
void gazebo::ServerFixture::SpawnRaySensor ( const std::string &  _modelName,
const std::string &  _raySensorName,
const math::Vector3 _pos,
const math::Vector3 _rpy,
double  _hMinAngle = -2.0,
double  _hMaxAngle = 2.0,
double  _vMinAngle = -1.0,
double  _vMaxAngle = 1.0,
double  _minRange = 0.08,
double  _maxRange = 10,
double  _rangeResolution = 0.01,
unsigned int  _samples = 640,
unsigned int  _vSamples = 1,
double  _hResolution = 1.0,
double  _vResolution = 1.0,
const std::string &  _noiseType = "",
double  _noiseMean = 0.0,
double  _noiseStdDev = 0.0 
)
protected

Spawn a laser.

Parameters
[in]_modelNameName of the model.
[in]_raySensorNameName of the laser.
[in]_posCamera position.
[in]_rpyCamera roll, pitch, yaw.
[in]_hMinAngleHorizontal min angle
[in]_hMaxAngleHorizontal max angle
[in]_minRangeMin range
[in]_maxRangeMax range
[in]_rangeResolutionResolution of the scan
[in]_samplesNumber of samples.
[in]_rateOutput Hz.
[in]_noiseTypeType of noise to apply.
[in]_noiseMeanMean noise value.
[in]_noiseStdDevStandard deviation of the noise.
void gazebo::ServerFixture::SpawnSDF ( const std::string &  _sdf)
protected

Send a factory message based on an SDF string.

Parameters
[in]_sdfSDF string to publish.
void gazebo::ServerFixture::SpawnSphere ( const std::string &  _name,
const math::Vector3 _pos,
const math::Vector3 _rpy,
bool  _wait = true,
bool  _static = false 
)
protected

Spawn a sphere.

Parameters
[in]_nameName for the model.
[in]_posPosition for the model.
[in]_rpyRoll, pitch, yaw for the model.
[in]_staticTrue to make the model static.
[in]_waitTrue to wait for the sphere to spawn before returning.
void gazebo::ServerFixture::SpawnSphere ( const std::string &  _name,
const math::Vector3 _pos,
const math::Vector3 _rpy,
const math::Vector3 _cog,
double  _radius,
bool  _wait = true,
bool  _static = false 
)
protected

Spawn a sphere.

Parameters
[in]_nameName for the model.
[in]_posPosition for the model.
[in]_rpyRoll, pitch, yaw for the model.
[in]_cogCenter of gravity.
[in]_radiusSphere radius.
[in]_staticTrue to make the model static.
[in]_waitTrue to wait for the sphere to spawn before returning.
void gazebo::ServerFixture::SpawnTrimesh ( const std::string &  _name,
const std::string &  _modelPath,
const math::Vector3 _scale,
const math::Vector3 _pos,
const math::Vector3 _rpy,
bool  _static = false 
)
protected

Spawn a triangle mesh.

Parameters
[in]_nameName for the model.
[in]_modelPathPath to the mesh file.
[in]_scaleScaling factor.
[in]_posPosition for the model.
[in]_rpyRoll, pitch, yaw for the model.
[in]_staticTrue to make the model static.
void gazebo::ServerFixture::SpawnUnitAltimeterSensor ( const std::string &  _name,
const std::string &  _sensorName,
const std::string &  _collisionType,
const std::string &  _topic,
const ignition::math::Vector3d &  _pos,
const ignition::math::Vector3d &  _rpy,
bool  _static = false 
)
protected

Spawn an altimeter sensor on a link.

Parameters
[in]_nameModel name
[in]_sensorNameSensor name
[in]_collisionTypeType of collision, box or cylinder
[in]_topicTopic to publish altimeter data to
[in]_posWorld position
[in]_rpyWorld rotation in Euler angles
[in]_staticTrue to make the model static
void gazebo::ServerFixture::SpawnUnitContactSensor ( const std::string &  _name,
const std::string &  _sensorName,
const std::string &  _collisionType,
const math::Vector3 _pos,
const math::Vector3 _rpy,
bool  _static = false 
)
protected

Spawn a contact sensor with the specified collision geometry.

Parameters
[in]_nameModel name
[in]_sensorNameSensor name
[in]_collisionTypeType of collision, box or cylinder
[in]_posWorld position
[in]_rpyWorld rotation in Euler angles
[in]_staticTrue to make the model static
void gazebo::ServerFixture::SpawnUnitImuSensor ( const std::string &  _name,
const std::string &  _sensorName,
const std::string &  _collisionType,
const std::string &  _topic,
const math::Vector3 _pos,
const math::Vector3 _rpy,
bool  _static = false 
)
protected

Spawn an IMU sensor on a link.

Parameters
[in]_nameModel name
[in]_sensorNameSensor name
[in]_collisionTypeType of collision, box or cylinder
[in]_topicTopic to publish IMU data to
[in]_posWorld position
[in]_rpyWorld rotation in Euler angles
[in]_staticTrue to make the model static
void gazebo::ServerFixture::SpawnUnitMagnetometerSensor ( const std::string &  _name,
const std::string &  _sensorName,
const std::string &  _collisionType,
const std::string &  _topic,
const ignition::math::Vector3d &  _pos,
const ignition::math::Vector3d &  _rpy,
bool  _static = false 
)
protected

Spawn a magnetometer sensor on a link.

Parameters
[in]_nameModel name
[in]_sensorNameSensor name
[in]_collisionTypeType of collision, box or cylinder
[in]_topicTopic to publish magnetometer data to
[in]_posWorld position
[in]_rpyWorld rotation in Euler angles
[in]_staticTrue to make the model static
void gazebo::ServerFixture::SpawnWirelessReceiverSensor ( const std::string &  _name,
const std::string &  _sensorName,
const math::Vector3 _pos,
const math::Vector3 _rpy,
double  _minFreq,
double  _maxFreq,
double  _power,
double  _gain,
double  _sensitivity,
bool  _visualize = true 
)
protected

Spawn an Wireless receiver sensor on a link.

Parameters
[in]_nameModel name
[in]_sensorNameSensor name
[in]_posWorld position
[in]_rpyWorld rotation in Euler angles
[in]_minFreqMinimum frequency to be filtered (MHz)
[in]_maxFreqMaximum frequency to be filtered (MHz)
[in]_powerTransmission power (dBm)
[in]_gainAntenna gain (dBi)
[in]_sensitivityReceiver sensitibity (dBm)
[in]_visualizeEnable sensor visualization
void gazebo::ServerFixture::SpawnWirelessTransmitterSensor ( const std::string &  _name,
const std::string &  _sensorName,
const math::Vector3 _pos,
const math::Vector3 _rpy,
const std::string &  _essid,
double  _freq,
double  _power,
double  _gain,
bool  _visualize = true 
)
protected

Spawn an Wireless transmitter sensor on a link.

Parameters
[in]_nameModel name
[in]_sensorNameSensor name
[in]_posWorld position
[in]_rpyWorld rotation in Euler angles
[in]_essidService set identifier (network name)
[in]_freqFrequency of transmission (MHz)
[in]_powerTransmission power (dBm)
[in]_gainAntenna gain (dBi)
[in]_visualizeEnable sensor visualization
virtual void gazebo::ServerFixture::TearDown ( )
protectedvirtual

Tear down the test fixture. This gets called by gtest.

virtual void gazebo::ServerFixture::Unload ( )
protectedvirtual

Unload the test fixture.

void gazebo::ServerFixture::WaitUntilEntitySpawn ( const std::string &  _name,
unsigned int  _sleepEach,
int  _retries 
)
protected

Wait for a number of ms.

and attempts until the entity is spawned

Parameters
[in]_nameModel name
[in]_sleepEachNumber of milliseconds to sleep in each iteration
[in]_retriesNumber of iterations until give up
void gazebo::ServerFixture::WaitUntilSensorSpawn ( const std::string &  _name,
unsigned int  _sleepEach,
int  _retries 
)
protected

Wait for a number of ms.

and attempts until the sensor is spawned

Parameters
[in]_nameSensor name
[in]_sleepEachNumber of milliseconds to sleep in each iteration
[in]_retriesNumber of iterations until give up

Member Data Documentation

transport::PublisherPtr gazebo::ServerFixture::factoryPub
protected

Factory publisher.

transport::NodePtr gazebo::ServerFixture::node
protected

Pointer to a node for communication.

common::Time gazebo::ServerFixture::pauseTime
protected
std::map<std::string, math::Pose> gazebo::ServerFixture::poses
protected

Map of received poses.

transport::SubscriberPtr gazebo::ServerFixture::poseSub
protected

Pose subscription.

common::Time gazebo::ServerFixture::realTime
protected
boost::mutex gazebo::ServerFixture::receiveMutex
protected

Mutex to protect data structures that store messages.

transport::PublisherPtr gazebo::ServerFixture::requestPub
protected

Request publisher.

Server* gazebo::ServerFixture::server
protected

Pointer the Gazebo server.

boost::thread* gazebo::ServerFixture::serverThread
protected

Pointer the thread the runs the server.

common::Time gazebo::ServerFixture::simTime
protected

Current simulation time, real time, and pause time.

transport::SubscriberPtr gazebo::ServerFixture::statsSub
protected

World statistics subscription.


The documentation for this class was generated from the following file: