#include <ServerFixture.hh>
Inherits ServerFixture.
Public Member Functions | |
virtual void | SetUp () |
Protected Member Functions | |
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... | |
virtual void | LoadArgs (const std::string &_args) |
Load a world in gzserver. 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::vector< std::string > &_args) |
Run the server. 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... | |
sensors::SonarSensorPtr | SpawnSonar (const std::string &_modelName, const std::string &_sonarName, const ignition::math::Pose3d &_pose, const double _minRange, const double _maxRange, const double _radius) |
Spawn a sonar. 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 | WaitUntilIteration (const uint32_t _goalIteration, const int _sleepEach, const int _retries) const |
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... | |
void | WaitUntilSimTime (const common::Time &_goalTime, const int _ms, const int _maxRetries) const |
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::Pose > | poses |
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... | |
Server * | server |
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... | |
|
inlinestaticprotectedinherited |
Check that a pointer is not NULL.
A function is created for this purpose, since ASSERT's cannot be called from non-void functions.
[in] | _ptr | Pointer to verify is not NULL. |
References NULL, Vector3::UnitZ, and Color::White.
|
protectedinherited |
Function to compare two double arrays (for example two laser scans).
[in] | _scanA | First double array. |
[in] | _scanB | Second double array. |
[in] | _sampleCount | Number of samples in each double array. |
[out] | _diffMax | Maximum difference between the two arrays. |
[out] | _diffSum | Sum of the differences between the two arrays. |
[out] | _diffAvg | Average difference between the two arrays. |
|
protectedinherited |
Function to compare two float arrays (for example two laser scans).
[in] | _scanA | First float array. |
[in] | _scanB | Second float array. |
[in] | _sampleCount | Number of samples in each float array. |
[out] | _diffMax | Maximum difference between the two arrays. |
[out] | _diffSum | Sum of the differences between the two arrays. |
[out] | _diffAvg | Average difference between the two arrays. |
|
protectedinherited |
Get the pose of an entity.
[in] | _name | Name of the entity. |
|
protectedinherited |
Get an image frame from a camera.
[in] | _cameraName | Name of the camera to get a frame from. |
[out] | _imgData | Array that receives the image data. |
[in] | _width | Width of the image frame. |
[in] | _height | Height of the image frame. |
|
protectedinherited |
Get the current memory information.
[out] | _resident | Resident memory. |
[out] | _share | Shared memory. |
|
protectedinherited |
Get a pointer to a model.
[in] | _name | Name of the model to get. |
|
protectedinherited |
Get the real-time factor.
|
protectedinherited |
Get a pointer to the rendering scene.
[in] | _sceneName | Name of the scene to get. |
|
protectedinherited |
Get unique string with a specified prefix.
[in] | _prefix | Prefix for unique string. |
|
protectedinherited |
Return true if the named entity exists.
[in] | _name | Name of the entity to check for. |
|
protectedinherited |
Function to compare two images.
[in] | _imageA | First image to compare. |
[in] | _imageB | Second image to compare. |
[in] | _width | Width of both images. |
[in] | _height | Height of both images. |
[in] | _depth | Depth of both images. |
[out] | _diffMax | Maximum difference between the two arrays. |
[out] | _diffSum | Sum of the differences between the two arrays. |
[out] | _diffAvg | Average difference between the two arrays. |
|
protectedvirtualinherited |
Load a world based on a filename.
[in] | _worldFilename | Name of the world to load. |
|
protectedvirtualinherited |
Load a world based on a filename and set simulation paused/un-paused.
[in] | _worldFilename | Name of the world to load. |
[in] | _paused | True to start the world paused. |
|
protectedvirtualinherited |
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)
[in] | _worldFilename | Name of the world to load. |
[in] | _paused | True to start the world paused. |
[in] | _physics | Name of the physics engine. |
[in] | _systemPlugins | Array of system plugins to load. |
|
protectedvirtualinherited |
Load a world in gzserver.
[in] | _args | Options for the server using the same syntax used in the command line. E.g.: "-u --verbose" will run gzserver paused and in verbose mode. |
|
protectedinherited |
Load a plugin.
[in] | _filename | Plugin filename to load. |
[in] | _name | Name to associate with with the plugin. |
|
protectedinherited |
Function that received poses messages from a running simulation.
[in] | _msg | Pose message. |
|
protectedinherited |
Function that received world stastics messages.
[in] | _msg | World statistics message. |
|
protectedinherited |
Print image data to screen.
This is used to generate test data.
[in] | _name | Name to associate with the printed data. |
[in] | _image | The raw image data. |
[in] | _width | Width of the image. |
[in] | _height | Height of the image. |
[in] | _depth | Pixel depth. |
|
protectedinherited |
Print laser scan to screen.
This is used to generate test data.
[in] | _name | Name to associate with the printed data. |
[in] | _scan | The laser scan data. |
[in] | _sampleCount | Number of samples in the scan data. |
|
protectedinherited |
Helper to record data to gtest xml output.
[in] | _name | Name of data. |
[in] | _data | Floating point number to store. |
|
protectedinherited |
Helper to record signal statistics to gtest xml output.
[in] | _prefix | Prefix string for data names. |
[in] | _stats | Signal statistics to store. |
|
protectedinherited |
Helper to record Vector3 signal statistics to gtest xml output.
[in] | _prefix | Prefix string for data names. |
[in] | _stats | Vector3 signal statistics to store. |
|
protectedinherited |
Remove a model by name.
[in] | _name | Name of the model to remove. |
|
protectedinherited |
Remove a plugin.
[in] | _name | Name of the plugin to remove. |
|
protectedinherited |
Run the server.
[in] | _args | Vector of options for the server using the same syntax used in the command line. E.g.: {"-u", "--verbose"} will run gzserver paused and in verbose mode. |
|
protectedinherited |
Set a running simulation paused/unpaused.
|
virtual |
|
protectedinherited |
Spawn a box.
[in] | _name | Name for the model. |
[in] | _size | Size of the box. |
[in] | _pos | Position for the model. |
[in] | _rpy | Roll, pitch, yaw for the model. |
[in] | _static | True to make the model static. |
|
protectedinherited |
Spawn a camera.
[in] | _modelName | Name of the model. |
[in] | _cameraName | Name of the camera. |
[in] | _pos | Camera position. |
[in] | _rpy | Camera roll, pitch, yaw. |
[in] | _width | Output image width. |
[in] | _height | Output image height. |
[in] | _rate | Output Hz. |
[in] | _noiseType | Type of noise to apply. |
[in] | _noiseMean | Mean noise value. |
[in] | _noiseStdDev | Standard deviation of the noise. |
[in] | _distortionK1 | Distortion coefficient k1. |
[in] | _distortionK2 | Distortion coefficient k2. |
[in] | _distortionK3 | Distortion coefficient k3. |
[in] | _distortionP1 | Distortion coefficient P1. |
[in] | _distortionP2 | Distortion coefficient p2. |
[in] | _cx | Normalized optical center x, used for distortion. |
[in] | _cy | Normalized optical center y, used for distortion. |
|
protectedinherited |
Spawn a cylinder.
[in] | _name | Name for the model. |
[in] | _pos | Position for the model. |
[in] | _rpy | Roll, pitch, yaw for the model. |
[in] | _static | True to make the model static. |
|
protectedinherited |
Spawn an empty link.
[in] | _name | Name for the model. |
[in] | _pos | Position for the model. |
[in] | _rpy | Roll, pitch, yaw for the model. |
[in] | _static | True to make the model static. |
|
protectedinherited |
Spawn a gpu laser.
[in] | _modelName | Name of the model. |
[in] | _raySensorName | Name of the laser. |
[in] | _pos | Camera position. |
[in] | _rpy | Camera roll, pitch, yaw. |
[in] | _hMinAngle | Horizontal min angle |
[in] | _hMaxAngle | Horizontal max angle |
[in] | _minRange | Min range |
[in] | _maxRange | Max range |
[in] | _rangeResolution | Resolution of the scan |
[in] | _samples | Number of samples. |
[in] | _rate | Output Hz. |
[in] | _noiseType | Type of noise to apply. |
[in] | _noiseMean | Mean noise value. |
[in] | _noiseStdDev | Standard deviation of the noise. |
|
protectedinherited |
Spawn an imu sensor laser.
[in] | _modelName | Name of the model. |
[in] | _imuSensorName | Name of the imu sensor. |
[in] | _pos | Camera position. |
[in] | _rpy | Camera roll, pitch, yaw. |
[in] | _noiseType | Type of noise to apply. |
[in] | _noiseMean | Mean noise value. |
[in] | _noiseStdDev | Standard deviation of the noise. |
[in] | _accelNoiseMean | Acceleration based noise mean. |
[in] | _accelNoiseStdDev | Acceleration based noise standard deviation. |
[in] | _accelBiasMean | Acceleration mean bias |
[in] | _accelBiasStdDev | Acceleration standard deviation bias |
|
protectedinherited |
Spawn a light.
[in] | _name | Name for the light. |
[in] | _size | Type of light - "spot", "directional", or "point". |
[in] | _pos | Position for the light. |
[in] | _rpy | Roll, pitch, yaw for the light. |
[in] | _diffuse | Diffuse color of the light. |
[in] | _specular | Specular color of the light. |
[in] | _direction | Direction of the light ("spot" and "directional"). |
[in] | _attenuationRange | Range of attenuation. |
[in] | _attenuationConstant | Constant component of attenuation |
[in] | _attenuationLinear | Linear component of attenuation |
[in] | _attenuationQuadratic | Quadratic component of attenuation |
[in] | _spotInnerAngle | Inner angle ("spot" only). |
[in] | _spotOuterAngle | Outer angle ("spot" only). |
[in] | _spotFallOff | Fall off ("spot" only). |
[in] | _castShadows | True to cast shadows. |
|
protectedinherited |
Spawn a model from a msgs::Model and return ModelPtr.
[in] | _msg | Model message. |
|
protectedinherited |
Spawn a model from file.
[in] | _filename | File to load a model from. |
|
protectedinherited |
Spawn a laser.
[in] | _modelName | Name of the model. |
[in] | _raySensorName | Name of the laser. |
[in] | _pos | Camera position. |
[in] | _rpy | Camera roll, pitch, yaw. |
[in] | _hMinAngle | Horizontal min angle |
[in] | _hMaxAngle | Horizontal max angle |
[in] | _minRange | Min range |
[in] | _maxRange | Max range |
[in] | _rangeResolution | Resolution of the scan |
[in] | _samples | Number of samples. |
[in] | _rate | Output Hz. |
[in] | _noiseType | Type of noise to apply. |
[in] | _noiseMean | Mean noise value. |
[in] | _noiseStdDev | Standard deviation of the noise. |
|
protectedinherited |
Send a factory message based on an SDF string.
[in] | _sdf | SDF string to publish. |
|
protectedinherited |
Spawn a sonar.
[in] | _modelName | Name of the model. |
[in] | _sonarName | Name of the sonar. |
[in] | _pose | Sonar pose. |
[in] | _minRange | Minimum sonar range. |
[in] | _maxRange | Maximum sonar range. |
[in] | _radius | Sonar cone radius. |
|
protectedinherited |
Spawn a sphere.
[in] | _name | Name for the model. |
[in] | _pos | Position for the model. |
[in] | _rpy | Roll, pitch, yaw for the model. |
[in] | _static | True to make the model static. |
[in] | _wait | True to wait for the sphere to spawn before returning. |
|
protectedinherited |
Spawn a sphere.
[in] | _name | Name for the model. |
[in] | _pos | Position for the model. |
[in] | _rpy | Roll, pitch, yaw for the model. |
[in] | _cog | Center of gravity. |
[in] | _radius | Sphere radius. |
[in] | _static | True to make the model static. |
[in] | _wait | True to wait for the sphere to spawn before returning. |
|
protectedinherited |
Spawn a triangle mesh.
[in] | _name | Name for the model. |
[in] | _modelPath | Path to the mesh file. |
[in] | _scale | Scaling factor. |
[in] | _pos | Position for the model. |
[in] | _rpy | Roll, pitch, yaw for the model. |
[in] | _static | True to make the model static. |
|
protectedinherited |
Spawn an altimeter sensor on a link.
[in] | _name | Model name |
[in] | _sensorName | Sensor name |
[in] | _collisionType | Type of collision, box or cylinder |
[in] | _topic | Topic to publish altimeter data to |
[in] | _pos | World position |
[in] | _rpy | World rotation in Euler angles |
[in] | _static | True to make the model static |
|
protectedinherited |
Spawn a contact sensor with the specified collision geometry.
[in] | _name | Model name |
[in] | _sensorName | Sensor name |
[in] | _collisionType | Type of collision, box or cylinder |
[in] | _pos | World position |
[in] | _rpy | World rotation in Euler angles |
[in] | _static | True to make the model static |
|
protectedinherited |
Spawn an IMU sensor on a link.
[in] | _name | Model name |
[in] | _sensorName | Sensor name |
[in] | _collisionType | Type of collision, box or cylinder |
[in] | _topic | Topic to publish IMU data to |
[in] | _pos | World position |
[in] | _rpy | World rotation in Euler angles |
[in] | _static | True to make the model static |
|
protectedinherited |
Spawn a magnetometer sensor on a link.
[in] | _name | Model name |
[in] | _sensorName | Sensor name |
[in] | _collisionType | Type of collision, box or cylinder |
[in] | _topic | Topic to publish magnetometer data to |
[in] | _pos | World position |
[in] | _rpy | World rotation in Euler angles |
[in] | _static | True to make the model static |
|
protectedinherited |
Spawn an Wireless receiver sensor on a link.
[in] | _name | Model name |
[in] | _sensorName | Sensor name |
[in] | _pos | World position |
[in] | _rpy | World rotation in Euler angles |
[in] | _minFreq | Minimum frequency to be filtered (MHz) |
[in] | _maxFreq | Maximum frequency to be filtered (MHz) |
[in] | _power | Transmission power (dBm) |
[in] | _gain | Antenna gain (dBi) |
[in] | _sensitivity | Receiver sensitibity (dBm) |
[in] | _visualize | Enable sensor visualization |
|
protectedinherited |
Spawn an Wireless transmitter sensor on a link.
[in] | _name | Model name |
[in] | _sensorName | Sensor name |
[in] | _pos | World position |
[in] | _rpy | World rotation in Euler angles |
[in] | _essid | Service set identifier (network name) |
[in] | _freq | Frequency of transmission (MHz) |
[in] | _power | Transmission power (dBm) |
[in] | _gain | Antenna gain (dBi) |
[in] | _visualize | Enable sensor visualization |
|
protectedvirtualinherited |
Tear down the test fixture. This gets called by gtest.
|
protectedvirtualinherited |
Unload the test fixture.
|
protectedinherited |
Wait for a number of ms.
and attempts until the entity is spawned
[in] | _name | Model name |
[in] | _sleepEach | Number of milliseconds to sleep in each iteration |
[in] | _retries | Number of iterations until give up |
|
protectedinherited |
Wait for a number of ms.
and attempts until the world reaches a target "iterations" value
_goalIteration | Target iterations value |
_sleepEach | Number of milliseconds to sleep in each iteration |
_retries | Number of iterations until give up |
|
protectedinherited |
Wait for a number of ms.
and attempts until the sensor is spawned
[in] | _name | Sensor name |
[in] | _sleepEach | Number of milliseconds to sleep in each iteration |
[in] | _retries | Number of iterations until give up |
|
protectedinherited |
Wait for a number of ms.
and attempts until the world reaches a target simulation time
_goalTime | Target simulation time. |
_sleepEach | Number of milliseconds to sleep in each iteration |
_retries | Number of iterations until give up |
|
protectedinherited |
Factory publisher.
|
protectedinherited |
Pointer to a node for communication.
|
protectedinherited |
|
protectedinherited |
Map of received poses.
|
protectedinherited |
Pose subscription.
|
protectedinherited |
|
protectedinherited |
Mutex to protect data structures that store messages.
|
protectedinherited |
Request publisher.
|
protectedinherited |
Pointer the Gazebo server.
|
protectedinherited |
Pointer the thread the runs the server.
|
protectedinherited |
Current simulation time, real time, and pause time.
|
protectedinherited |
World statistics subscription.