|  | 
|  | 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... 
 | 
|  | 
| 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... 
 | 
|  | 
| template<typename T > | 
| static void | CheckPointer (boost::shared_ptr< T > _ptr) | 
|  | Check that a pointer is not NULL.  More... 
 | 
|  | 
| 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... 
 | 
|  |