ServerFixture.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef _GAZEBO_SERVER_FIXTURE_HH_
18 #define _GAZEBO_SERVER_FIXTURE_HH_
19 
20 #pragma GCC diagnostic ignored "-Wswitch-default"
21 #pragma GCC diagnostic ignored "-Wfloat-equal"
22 #pragma GCC diagnostic ignored "-Wshadow"
23 
24 // The following is needed to enable the GetMemInfo function for OSX
25 #ifdef __MACH__
26 # include <mach/mach.h>
27 #endif // __MACH__
28 
29 #include <sdf/sdf.hh>
30 
31 #include <gtest/gtest.h>
32 #include <boost/thread.hpp>
33 #include <mutex>
34 #include <boost/filesystem.hpp>
35 
36 #include <map>
37 #include <string>
38 #include <vector>
39 
40 #include <ignition/math/Pose3.hh>
41 #include <ignition/math/SignalStats.hh>
42 #include <ignition/math/Vector3Stats.hh>
43 
44 #include "gazebo/transport/transport.hh"
45 
48 #include "gazebo/common/Console.hh"
49 #include "gazebo/physics/World.hh"
52 #include "gazebo/sensors/sensors.hh"
53 #include "gazebo/rendering/rendering.hh"
54 #include "gazebo/msgs/msgs.hh"
55 
58 
59 #include "gazebo/gazebo_config.h"
60 #include "gazebo/Server.hh"
61 #include "gazebo/util/system.hh"
62 
63 #include "test_config.h"
64 
65 namespace gazebo
66 {
67  std::string custom_exec(std::string _cmd);
68 
69  class GAZEBO_VISIBLE ServerFixture : public testing::Test
70  {
72  protected: ServerFixture();
73 
75  protected: virtual ~ServerFixture();
76 
78  protected: virtual void TearDown();
79 
81  protected: virtual void Unload();
82 
85  protected: virtual void Load(const std::string &_worldFilename);
86 
91  protected: virtual void Load(const std::string &_worldFilename,
92  bool _paused);
93 
101  protected: virtual void Load(const std::string &_worldFilename,
102  bool _paused, const std::string &_physics,
103  const std::vector<std::string> &_systemPlugins = {});
104 
109  protected: virtual void LoadArgs(const std::string &_args);
110 
115  protected: void RunServer(const std::vector<std::string> &_args);
116 
119  protected: rendering::ScenePtr GetScene(
120  const std::string &_sceneName = "default");
121 
124  protected: void OnStats(ConstWorldStatisticsPtr &_msg);
125 
127  protected: void SetPause(bool _pause);
128 
131  protected: double GetPercentRealTime() const;
132 
136  protected: void OnPose(ConstPosesStampedPtr &_msg);
137 
143  protected: math::Pose GetEntityPose(const std::string &_name)
144  GAZEBO_DEPRECATED(8.0);
145 
149  protected: ignition::math::Pose3d EntityPose(
150  const std::string &_name);
151 
155  protected: bool HasEntity(const std::string &_name);
156 
163  protected: void PrintImage(const std::string &_name, unsigned char **_image,
164  unsigned int _width, unsigned int _height,
165  unsigned int _depth);
166 
171  protected: void PrintScan(const std::string &_name, double *_scan,
172  unsigned int _sampleCount);
173 
182  protected: void FloatCompare(float *_scanA, float *_scanB,
183  unsigned int _sampleCount, float &_diffMax,
184  float &_diffSum, float &_diffAvg);
185 
194  protected: void DoubleCompare(double *_scanA, double *_scanB,
195  unsigned int _sampleCount, double &_diffMax,
196  double &_diffSum, double &_diffAvg);
197 
207  protected: void ImageCompare(unsigned char *_imageA,
208  unsigned char *_imageB,
209  unsigned int _width, unsigned int _height,
210  unsigned int _depth,
211  unsigned int &_diffMax, unsigned int &_diffSum,
212  double &_diffAvg);
213 
220  private: void OnNewFrame(const unsigned char *_image,
221  unsigned int _width, unsigned int _height,
222  unsigned int _depth,
223  const std::string &/*_format*/);
224 
230  protected: void GetFrame(const std::string &_cameraName,
231  unsigned char **_imgData, unsigned int &_width,
232  unsigned int &_height);
233 
237  protected: physics::ModelPtr SpawnModel(const msgs::Model &_msg);
238 
243  protected: template<typename T>
244  static void CheckPointer(boost::shared_ptr<T> _ptr)
245  {
246  ASSERT_TRUE(_ptr != NULL);
247  }
248 
268  protected: void SpawnCamera(const std::string &_modelName,
269  const std::string &_cameraName,
270  const math::Vector3 &_pos, const math::Vector3 &_rpy,
271  unsigned int _width = 320, unsigned int _height = 240,
272  double _rate = 25,
273  const std::string &_noiseType = "",
274  double _noiseMean = 0.0, double _noiseStdDev = 0.0,
275  bool _distortion = false, double _distortionK1 = 0.0,
276  double _distortionK2 = 0.0, double _distortionK3 = 0.0,
277  double _distortionP1 = 0.0, double _distortionP2 = 0.0,
278  double _cx = 0.5, double _cy = 0.5)
279  GAZEBO_DEPRECATED(8.0)
280  {
281 #ifndef _WIN32
282  #pragma GCC diagnostic push
283  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
284 #endif
285  SpawnCamera(_modelName, _cameraName, _pos.Ign(), _rpy.Ign(),
286  _width, _height, _rate, _noiseType, _noiseMean,
287  _noiseStdDev , _distortion , _distortionK1,
288  _distortionK2, _distortionK3, _distortionP1,
289  _distortionP2, _cx, _cy);
290 #ifndef _WIN32
291  #pragma GCC diagnostic pop
292 #endif
293  }
294 
313  protected: void SpawnCamera(const std::string &_modelName,
314  const std::string &_cameraName,
315  const ignition::math::Vector3d &_pos =
316  ignition::math::Vector3d::Zero,
317  const ignition::math::Vector3d &_rpy =
318  ignition::math::Vector3d::Zero,
319  unsigned int _width = 320, unsigned int _height = 240,
320  double _rate = 25,
321  const std::string &_noiseType = "",
322  double _noiseMean = 0.0, double _noiseStdDev = 0.0,
323  bool _distortion = false, double _distortionK1 = 0.0,
324  double _distortionK2 = 0.0, double _distortionK3 = 0.0,
325  double _distortionP1 = 0.0, double _distortionP2 = 0.0,
326  double _cx = 0.5, double _cy = 0.5);
327 
351  protected: void SpawnWideAngleCamera(const std::string &_modelName,
352  const std::string &_cameraName,
353  const ignition::math::Vector3d &_pos =
354  ignition::math::Vector3d::Zero,
355  const ignition::math::Vector3d &_rpy =
356  ignition::math::Vector3d::Zero,
357  unsigned int _width = 320,
358  unsigned int _height = 240,
359  double _rate = 25,
360  const double _hfov = 60,
361  const std::string &_lensType = "stereographic",
362  const bool _scaleToHfov = true,
363  const double _cutoffAngle = 3.1415,
364  const double _envTextureSize = 512,
365  const double _c1 = 1.05, const double _c2 = 4,
366  const double _f = 1.0,
367  const std::string &_fun = "tan");
368 
385  protected: void SpawnRaySensor(const std::string &_modelName,
386  const std::string &_raySensorName,
387  const math::Vector3 &_pos,
388  const math::Vector3 &_rpy,
389  double _hMinAngle = -2.0, double _hMaxAngle = 2.0,
390  double _vMinAngle = -1.0, double _vMaxAngle = 1.0,
391  double _minRange = 0.08, double _maxRange = 10,
392  double _rangeResolution = 0.01, unsigned int _samples = 640,
393  unsigned int _vSamples = 1, double _hResolution = 1.0,
394  double _vResolution = 1.0,
395  const std::string &_noiseType = "", double _noiseMean = 0.0,
396  double _noiseStdDev = 0.0)
397  GAZEBO_DEPRECATED(8.0)
398  {
399 #ifndef _WIN32
400  #pragma GCC diagnostic push
401  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
402 #endif
403  SpawnRaySensor(_modelName, _raySensorName, _pos.Ign(),
404  _rpy.Ign(), _hMinAngle, _hMaxAngle, _vMinAngle,
405  _vMaxAngle, _minRange, _maxRange , _rangeResolution,
406  _samples, _vSamples, _hResolution, _vResolution,
407  _noiseType, _noiseMean, _noiseStdDev);
408 #ifndef _WIN32
409  #pragma GCC diagnostic pop
410 #endif
411  }
412 
428  protected: void SpawnRaySensor(const std::string &_modelName,
429  const std::string &_raySensorName,
430  const ignition::math::Vector3d &_pos =
431  ignition::math::Vector3d::Zero,
432  const ignition::math::Vector3d &_rpy =
433  ignition::math::Vector3d::Zero,
434  double _hMinAngle = -2.0, double _hMaxAngle = 2.0,
435  double _vMinAngle = -1.0, double _vMaxAngle = 1.0,
436  double _minRange = 0.08, double _maxRange = 10,
437  double _rangeResolution = 0.01, unsigned int _samples = 640,
438  unsigned int _vSamples = 1, double _hResolution = 1.0,
439  double _vResolution = 1.0,
440  const std::string &_noiseType = "", double _noiseMean = 0.0,
441  double _noiseStdDev = 0.0);
442 
450  protected: sensors::SonarSensorPtr SpawnSonar(const std::string &_modelName,
451  const std::string &_sonarName,
452  const ignition::math::Pose3d &_pose,
453  const double _minRange,
454  const double _maxRange,
455  const double _radius);
456 
473  protected: void SpawnGpuRaySensor(const std::string &_modelName,
474  const std::string &_raySensorName,
475  const math::Vector3 &_pos, const math::Vector3 &_rpy,
476  double _hMinAngle = -2.0, double _hMaxAngle = 2.0,
477  double _minRange = 0.08, double _maxRange = 10,
478  double _rangeResolution = 0.01, unsigned int _samples = 640,
479  const std::string &_noiseType = "", double _noiseMean = 0.0,
480  double _noiseStdDev = 0.0)
481  GAZEBO_DEPRECATED(8.0)
482  {
483 #ifndef _WIN32
484  #pragma GCC diagnostic push
485  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
486 #endif
487  SpawnGpuRaySensor(_modelName, _raySensorName, _pos.Ign(),
488  _rpy.Ign(), _hMinAngle, _hMaxAngle, _minRange, _maxRange,
489  _rangeResolution, _samples, _noiseType, _noiseMean,
490  _noiseStdDev);
491 #ifndef _WIN32
492  #pragma GCC diagnostic pop
493 #endif
494  }
495 
496 
512  protected: void SpawnGpuRaySensor(const std::string &_modelName,
513  const std::string &_raySensorName,
514  const ignition::math::Vector3d &_pos =
515  ignition::math::Vector3d::Zero,
516  const ignition::math::Vector3d &_rpy =
517  ignition::math::Vector3d::Zero,
518  double _hMinAngle = -2.0, double _hMaxAngle = 2.0,
519  double _minRange = 0.08, double _maxRange = 10,
520  double _rangeResolution = 0.01, unsigned int _samples = 640,
521  const std::string &_noiseType = "", double _noiseMean = 0.0,
522  double _noiseStdDev = 0.0);
523 
534  protected: void SpawnDepthCameraSensor(const std::string &_modelName,
535  const std::string &_cameraName,
536  const ignition::math::Vector3d &_pos =
537  ignition::math::Vector3d::Zero,
538  const ignition::math::Vector3d &_rpy =
539  ignition::math::Vector3d::Zero,
540  const unsigned int _width = 320,
541  const unsigned int _height = 240,
542  const double _rate = 25, const double _near = 0.1,
543  const double _far = 10);
544 
559  protected: void SpawnImuSensor(const std::string &_modelName,
560  const std::string &_imuSensorName,
561  const math::Vector3 &_pos, const math::Vector3 &_rpy,
562  const std::string &_noiseType = "",
563  double _rateNoiseMean = 0.0, double _rateNoiseStdDev = 0.0,
564  double _rateBiasMean = 0.0, double _rateBiasStdDev = 0.0,
565  double _accelNoiseMean = 0.0, double _accelNoiseStdDev = 0.0,
566  double _accelBiasMean = 0.0, double _accelBiasStdDev = 0.0)
567  GAZEBO_DEPRECATED(8.0)
568  {
569 #ifndef _WIN32
570  #pragma GCC diagnostic push
571  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
572 #endif
573  SpawnImuSensor(_modelName, _imuSensorName, _pos.Ign(),
574  _rpy.Ign(), _noiseType, _rateNoiseMean,
575  _rateNoiseStdDev, _rateBiasMean, _rateBiasStdDev,
576  _accelNoiseMean, _accelNoiseStdDev, _accelBiasMean,
577  _accelBiasStdDev);
578 #ifndef _WIN32
579  #pragma GCC diagnostic pop
580 #endif
581  }
582 
596  protected: void SpawnImuSensor(const std::string &_modelName,
597  const std::string &_imuSensorName,
598  const ignition::math::Vector3d &_pos =
599  ignition::math::Vector3d::Zero,
600  const ignition::math::Vector3d &_rpy =
601  ignition::math::Vector3d::Zero,
602  const std::string &_noiseType = "",
603  double _rateNoiseMean = 0.0, double _rateNoiseStdDev = 0.0,
604  double _rateBiasMean = 0.0, double _rateBiasStdDev = 0.0,
605  double _accelNoiseMean = 0.0, double _accelNoiseStdDev = 0.0,
606  double _accelBiasMean = 0.0, double _accelBiasStdDev = 0.0);
607 
616  protected: void SpawnUnitContactSensor(const std::string &_name,
617  const std::string &_sensorName,
618  const std::string &_collisionType, const math::Vector3 &_pos,
619  const math::Vector3 &_rpy, bool _static = false)
620  GAZEBO_DEPRECATED(8.0)
621  {
622 #ifndef _WIN32
623  #pragma GCC diagnostic push
624  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
625 #endif
626  SpawnUnitContactSensor(_name, _sensorName, _collisionType,
627  _pos.Ign(), _rpy.Ign(), _static);
628 #ifndef _WIN32
629  #pragma GCC diagnostic pop
630 #endif
631  }
632 
640  protected: void SpawnUnitContactSensor(const std::string &_name,
641  const std::string &_sensorName,
642  const std::string &_collisionType,
643  const ignition::math::Vector3d &_pos =
644  ignition::math::Vector3d::Zero,
645  const ignition::math::Vector3d &_rpy =
646  ignition::math::Vector3d::Zero,
647  bool _static = false);
648 
658  protected: void SpawnUnitImuSensor(const std::string &_name,
659  const std::string &_sensorName,
660  const std::string &_collisionType,
661  const std::string &_topic, const math::Vector3 &_pos,
662  const math::Vector3 &_rpy, bool _static = false)
663  GAZEBO_DEPRECATED(8.0)
664  {
665 #ifndef _WIN32
666  #pragma GCC diagnostic push
667  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
668 #endif
669  SpawnUnitImuSensor(_name, _sensorName, _collisionType,
670  _topic, _pos.Ign(), _rpy.Ign(), _static);
671 #ifndef _WIN32
672  #pragma GCC diagnostic pop
673 #endif
674  }
675 
684  protected: void SpawnUnitImuSensor(const std::string &_name,
685  const std::string &_sensorName,
686  const std::string &_collisionType,
687  const std::string &_topic,
688  const ignition::math::Vector3d &_pos =
689  ignition::math::Vector3d::Zero,
690  const ignition::math::Vector3d &_rpy =
691  ignition::math::Vector3d::Zero,
692  bool _static = false);
693 
702  protected: void SpawnUnitAltimeterSensor(const std::string &_name,
703  const std::string &_sensorName,
704  const std::string &_collisionType,
705  const std::string &_topic,
706  const ignition::math::Vector3d &_pos =
707  ignition::math::Vector3d::Zero,
708  const ignition::math::Vector3d &_rpy =
709  ignition::math::Vector3d::Zero,
710  bool _static = false);
711 
720  protected: void SpawnUnitMagnetometerSensor(const std::string &_name,
721  const std::string &_sensorName,
722  const std::string &_collisionType,
723  const std::string &_topic,
724  const ignition::math::Vector3d &_pos =
725  ignition::math::Vector3d::Zero,
726  const ignition::math::Vector3d &_rpy =
727  ignition::math::Vector3d::Zero,
728  bool _static = false);
729 
734  private: void launchTimeoutFailure(const char *_logMsg,
735  const int _timeoutCS);
736 
748  protected: void SpawnWirelessTransmitterSensor(const std::string &_name,
749  const std::string &_sensorName,
750  const math::Vector3 &_pos,
751  const math::Vector3 &_rpy,
752  const std::string &_essid,
753  double _freq,
754  double _power,
755  double _gain,
756  bool _visualize = true)
757  GAZEBO_DEPRECATED(8.0)
758  {
759 #ifndef _WIN32
760  #pragma GCC diagnostic push
761  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
762 #endif
763  SpawnWirelessTransmitterSensor(_name, _sensorName,
764  _pos.Ign(), _rpy.Ign(), _essid, _freq, _power,
765  _gain, _visualize);
766 #ifndef _WIN32
767  #pragma GCC diagnostic pop
768 #endif
769  }
770 
781  protected: void SpawnWirelessTransmitterSensor(const std::string &_name,
782  const std::string &_sensorName,
783  const ignition::math::Vector3d &_pos,
784  const ignition::math::Vector3d &_rpy,
785  const std::string &_essid,
786  double _freq,
787  double _power,
788  double _gain,
789  bool _visualize = true);
790 
803  protected: void SpawnWirelessReceiverSensor(const std::string &_name,
804  const std::string &_sensorName,
805  const math::Vector3 &_pos,
806  const math::Vector3 &_rpy,
807  double _minFreq,
808  double _maxFreq,
809  double _power,
810  double _gain,
811  double _sensitivity,
812  bool _visualize = true)
813  GAZEBO_DEPRECATED(8.0)
814  {
815 #ifndef _WIN32
816  #pragma GCC diagnostic push
817  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
818 #endif
819  SpawnWirelessReceiverSensor(_name, _sensorName, _pos.Ign(),
820  _rpy.Ign(), _minFreq, _maxFreq, _power, _gain,
821  _sensitivity, _visualize);
822 #ifndef _WIN32
823  #pragma GCC diagnostic pop
824 #endif
825  }
826 
838  protected: void SpawnWirelessReceiverSensor(const std::string &_name,
839  const std::string &_sensorName,
840  const ignition::math::Vector3d &_pos,
841  const ignition::math::Vector3d &_rpy,
842  double _minFreq,
843  double _maxFreq,
844  double _power,
845  double _gain,
846  double _sensitivity,
847  bool _visualize = true);
848 
853  protected: void WaitUntilEntitySpawn(const std::string &_name,
854  unsigned int _sleepEach,
855  int _retries);
856 
861  protected: void WaitUntilSensorSpawn(const std::string &_name,
862  unsigned int _sleepEach,
863  int _retries);
864 
870  protected: void WaitUntilIteration(const uint32_t _goalIteration,
871  const int _sleepEach,
872  const int _retries) const;
873 
879  protected: void WaitUntilSimTime(const common::Time &_goalTime,
880  const int _ms,
881  const int _maxRetries) const;
882 
900 #ifndef _WIN32
901  #pragma GCC diagnostic push
902  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
903 #endif
904  protected: void SpawnLight(const std::string &_name,
905  const std::string &_type,
906  const math::Vector3 &_pos, const math::Vector3 &_rpy,
907  const common::Color &_diffuse = common::Color::White,
908  const common::Color &_specular = common::Color::White,
909  const math::Vector3 &_direction = -math::Vector3::UnitZ,
910  double _attenuationRange = 20,
911  double _attenuationConstant = 0.5,
912  double _attenuationLinear = 0.01,
913  double _attenuationQuadratic = 0.001,
914  double _spotInnerAngle = 0,
915  double _spotOuterAngle = 0,
916  double _spotFallOff = 0,
917  bool _castShadows = true)
918  GAZEBO_DEPRECATED(8.0)
919  {
920  SpawnLight(_name, _type, _pos.Ign(), _rpy.Ign(), _diffuse,
921  _specular, _direction.Ign(), _attenuationRange,
922  _attenuationConstant, _attenuationLinear,
923  _attenuationQuadratic, _spotInnerAngle,
924  _spotOuterAngle, _spotFallOff, _castShadows);
925  }
926 #ifndef _WIN32
927  #pragma GCC diagnostic pop
928 #endif
929 
946  protected: void SpawnLight(const std::string &_name,
947  const std::string &_type,
948  const ignition::math::Vector3d &_pos =
949  ignition::math::Vector3d::Zero,
950  const ignition::math::Vector3d &_rpy =
951  ignition::math::Vector3d::Zero,
952  const common::Color &_diffuse = common::Color::White,
953  const common::Color &_specular = common::Color::White,
954  const ignition::math::Vector3d &_direction =
955  -ignition::math::Vector3d::UnitZ,
956  double _attenuationRange = 20,
957  double _attenuationConstant = 0.5,
958  double _attenuationLinear = 0.01,
959  double _attenuationQuadratic = 0.001,
960  double _spotInnerAngle = 0,
961  double _spotOuterAngle = 0,
962  double _spotFallOff = 0,
963  bool _castShadows = true);
964 
971  protected: void SpawnCylinder(const std::string &_name,
972  const math::Vector3 &_pos, const math::Vector3 &_rpy,
973  bool _static = false)
974  GAZEBO_DEPRECATED(8.0)
975  {
976 #ifndef _WIN32
977  #pragma GCC diagnostic push
978  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
979 #endif
980  SpawnCylinder(_name, _pos.Ign(), _rpy.Ign(), _static);
981 #ifndef _WIN32
982  #pragma GCC diagnostic pop
983 #endif
984  }
985 
986 
992  protected: void SpawnCylinder(const std::string &_name,
993  const ignition::math::Vector3d &_pos =
994  ignition::math::Vector3d::Zero,
995  const ignition::math::Vector3d &_rpy =
996  ignition::math::Vector3d::Zero,
997  bool _static = false);
998 
1007  protected: void SpawnSphere(const std::string &_name,
1008  const math::Vector3 &_pos, const math::Vector3 &_rpy,
1009  bool _wait = true, bool _static = false)
1010  GAZEBO_DEPRECATED(8.0)
1011  {
1012 #ifndef _WIN32
1013  #pragma GCC diagnostic push
1014  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
1015 #endif
1016  SpawnSphere(_name, _pos.Ign(), _rpy.Ign(), _wait,
1017  _static);
1018 #ifndef _WIN32
1019  #pragma GCC diagnostic pop
1020 #endif
1021  }
1022 
1030  protected: void SpawnSphere(const std::string &_name,
1031  const ignition::math::Vector3d &_pos,
1032  const ignition::math::Vector3d &_rpy,
1033  bool _wait = true, bool _static = false);
1034 
1045  protected: void SpawnSphere(const std::string &_name,
1046  const math::Vector3 &_pos, const math::Vector3 &_rpy,
1047  const math::Vector3 &_cog, double _radius,
1048  bool _wait = true, bool _static = false)
1049  GAZEBO_DEPRECATED(8.0)
1050  {
1051 #ifndef _WIN32
1052  #pragma GCC diagnostic push
1053  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
1054 #endif
1055  SpawnSphere(_name, _pos.Ign(), _rpy.Ign(), _cog.Ign(),
1056  _radius, _wait, _static);
1057 #ifndef _WIN32
1058  #pragma GCC diagnostic pop
1059 #endif
1060  }
1061 
1062 
1072  protected: void SpawnSphere(const std::string &_name,
1073  const ignition::math::Vector3d &_pos,
1074  const ignition::math::Vector3d &_rpy,
1075  const ignition::math::Vector3d &_cog,
1076  double _radius = 1.0,
1077  bool _wait = true, bool _static = false);
1078 
1086  protected: void SpawnBox(const std::string &_name,
1087  const math::Vector3 &_size, const math::Vector3 &_pos,
1088  const math::Vector3 &_rpy, bool _static = false)
1089  GAZEBO_DEPRECATED(8.0)
1090  {
1091 #ifndef _WIN32
1092  #pragma GCC diagnostic push
1093  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
1094 #endif
1095  SpawnBox(_name, _size.Ign(), _pos.Ign(), _rpy.Ign(),
1096  _static);
1097 #ifndef _WIN32
1098  #pragma GCC diagnostic pop
1099 #endif
1100  }
1101 
1102 
1109  protected: void SpawnBox(const std::string &_name,
1110  const ignition::math::Vector3d &_size =
1111  ignition::math::Vector3d::One,
1112  const ignition::math::Vector3d &_pos =
1113  ignition::math::Vector3d::Zero,
1114  const ignition::math::Vector3d &_rpy =
1115  ignition::math::Vector3d::Zero,
1116  bool _static = false);
1117 
1126  protected: void SpawnTrimesh(const std::string &_name,
1127  const std::string &_modelPath, const math::Vector3 &_scale,
1128  const math::Vector3 &_pos, const math::Vector3 &_rpy,
1129  bool _static = false)
1130  GAZEBO_DEPRECATED(8.0)
1131  {
1132 #ifndef _WIN32
1133  #pragma GCC diagnostic push
1134  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
1135 #endif
1136  SpawnTrimesh(_name, _modelPath, _scale.Ign(), _pos.Ign(),
1137  _rpy.Ign(), _static);
1138 #ifndef _WIN32
1139  #pragma GCC diagnostic pop
1140 #endif
1141  }
1142 
1150  protected: void SpawnTrimesh(const std::string &_name,
1151  const std::string &_modelPath,
1152  const ignition::math::Vector3d &_scale =
1153  ignition::math::Vector3d::One,
1154  const ignition::math::Vector3d &_pos =
1155  ignition::math::Vector3d::Zero,
1156  const ignition::math::Vector3d &_rpy =
1157  ignition::math::Vector3d::Zero,
1158  bool _static = false);
1159 
1166  protected: void SpawnEmptyLink(const std::string &_name,
1167  const math::Vector3 &_pos, const math::Vector3 &_rpy,
1168  bool _static = false)
1169  GAZEBO_DEPRECATED(8.0)
1170  {
1171 #ifndef _WIN32
1172  #pragma GCC diagnostic push
1173  #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
1174 #endif
1175  SpawnEmptyLink(_name, _pos.Ign(), _rpy.Ign(), _static);
1176 #ifndef _WIN32
1177  #pragma GCC diagnostic pop
1178 #endif
1179  }
1180 
1181 
1187  protected: void SpawnEmptyLink(const std::string &_name,
1188  const ignition::math::Vector3d &_pos =
1189  ignition::math::Vector3d::Zero,
1190  const ignition::math::Vector3d &_rpy =
1191  ignition::math::Vector3d::Zero,
1192  bool _static = false);
1193 
1196  protected: void SpawnModel(const std::string &_filename);
1197 
1200  protected: void SpawnSDF(const std::string &_sdf);
1201 
1205  protected: void LoadPlugin(const std::string &_filename,
1206  const std::string &_name);
1207 
1211  protected: physics::ModelPtr GetModel(const std::string &_name);
1212 
1215  protected: void RemoveModel(const std::string &_name);
1216 
1219  protected: void RemovePlugin(const std::string &_name);
1220 
1224  protected: void GetMemInfo(double &_resident, double &_share);
1225 
1229  protected: std::string GetUniqueString(const std::string &_prefix);
1230 
1234  protected: void Record(const std::string &_name, const double _data);
1235 
1239  protected: void Record(const std::string &_prefix,
1240  const ignition::math::SignalStats &_stats);
1241 
1245  protected: void Record(const std::string &_prefix,
1246  const ignition::math::Vector3Stats &_stats);
1247 
1249  protected: Server *server;
1250 
1252  protected: boost::thread *serverThread;
1253 
1256 
1259 
1262 
1265 
1268 
1270  protected: std::map<std::string, ignition::math::Pose3d> poses;
1271 
1273  protected: std::mutex receiveMutex;
1274 
1276  private: unsigned char **imgData;
1277 
1279  private: int gotImage;
1280 
1282  protected: common::Time simTime, realTime, pauseTime;
1283 
1285  private: double percentRealTime;
1286 
1288  private: bool paused;
1289 
1291  private: bool serverRunning;
1292 
1294  private: int uniqueCounter;
1295  };
1296 
1298  {
1299  // Documentation inherited.
1300  public: virtual void SetUp();
1301 
1302  // Documentation inherited.
1303  protected: virtual void Unload();
1304  };
1305 } // namespace gazebo
1306 #endif // define _GAZEBO_SERVER_FIXTURE_HH_
transport::SubscriberPtr statsSub
World statistics subscription.
Definition: ServerFixture.hh:1261
static const Color White
(1, 1, 1)
Definition: Color.hh:39
transport::SubscriberPtr poseSub
Pose subscription.
Definition: ServerFixture.hh:1258
Encapsulates a position and rotation in three space.
Definition: Pose.hh:42
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:44
void SpawnSphere(const std::string &_name, const math::Vector3 &_pos, const math::Vector3 &_rpy, bool _wait=true, bool _static=false) GAZEBO_DEPRECATED(8.0)
Spawn a sphere.
Definition: ServerFixture.hh:1007
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) GAZEBO_DEPRECATED(8.0)
Spawn an imu sensor laser.
Definition: ServerFixture.hh:559
Definition: ServerFixture.hh:69
std::string custom_exec(std::string _cmd)
transport::PublisherPtr factoryPub
Factory publisher.
Definition: ServerFixture.hh:1264
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
void SpawnBox(const std::string &_name, const math::Vector3 &_size, const math::Vector3 &_pos, const math::Vector3 &_rpy, bool _static=false) GAZEBO_DEPRECATED(8.0)
Spawn a box.
Definition: ServerFixture.hh:1086
boost::thread * serverThread
Pointer the thread the runs the server.
Definition: ServerFixture.hh:1252
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) GAZEBO_DEPRECATED(8.0)
Spawn a camera.
Definition: ServerFixture.hh:268
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) GAZEBO_DEPRECATED(8.0)
Spawn a light.
Definition: ServerFixture.hh:904
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) GAZEBO_DEPRECATED(8.0)
Spawn a contact sensor with the specified collision geometry.
Definition: ServerFixture.hh:616
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
default namespace for gazebo
transport::NodePtr node
Pointer to a node for communication.
Definition: ServerFixture.hh:1255
Definition: ServerFixture.hh:1297
boost::shared_ptr< Scene > ScenePtr
Definition: RenderTypes.hh:81
common::Time simTime
Current simulation time, real time, and pause time.
Definition: ServerFixture.hh:1282
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) GAZEBO_DEPRECATED(8.0)
Spawn a laser.
Definition: ServerFixture.hh:385
std::mutex receiveMutex
Mutex to protect data structures that store messages.
Definition: ServerFixture.hh:1273
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) GAZEBO_DEPRECATED(8.0)
Spawn a gpu laser.
Definition: ServerFixture.hh:473
static const Vector3 UnitZ
math::Vector3(0, 0, 1)
Definition: Vector3.hh:59
static void CheckPointer(boost::shared_ptr< T > _ptr)
Check that a pointer is not NULL.
Definition: ServerFixture.hh:244
std::map< std::string, ignition::math::Pose3d > poses
Map of received poses.
Definition: ServerFixture.hh:1270
#define NULL
Definition: CommonTypes.hh:31
Defines a color.
Definition: Color.hh:36
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) GAZEBO_DEPRECATED(8.0)
Spawn a sphere.
Definition: ServerFixture.hh:1045
#define GAZEBO_DEPRECATED(version)
Definition: system.hh:302
transport::PublisherPtr requestPub
Request publisher.
Definition: ServerFixture.hh:1267
Server * server
Pointer the Gazebo server.
Definition: ServerFixture.hh:1249
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:93
Definition: Server.hh:41
ignition::math::Vector3d Ign() const GAZEBO_DEPRECATED(8.0)
Convert this vector to an ignition::math::Vector3d.
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) GAZEBO_DEPRECATED(8.0)
Spawn an Wireless receiver sensor on a link.
Definition: ServerFixture.hh:803
void SpawnEmptyLink(const std::string &_name, const math::Vector3 &_pos, const math::Vector3 &_rpy, bool _static=false) GAZEBO_DEPRECATED(8.0)
Spawn an empty link.
Definition: ServerFixture.hh:1166
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) GAZEBO_DEPRECATED(8.0)
Spawn a triangle mesh.
Definition: ServerFixture.hh:1126
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) GAZEBO_DEPRECATED(8.0)
Spawn an Wireless transmitter sensor on a link.
Definition: ServerFixture.hh:748
std::shared_ptr< SonarSensor > SonarSensorPtr
Definition: SensorTypes.hh:112
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:58
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) GAZEBO_DEPRECATED(8.0)
Spawn an IMU sensor on a link.
Definition: ServerFixture.hh:658
void SpawnCylinder(const std::string &_name, const math::Vector3 &_pos, const math::Vector3 &_rpy, bool _static=false) GAZEBO_DEPRECATED(8.0)
Spawn a cylinder.
Definition: ServerFixture.hh:971
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:44