17 #ifndef _GAZEBO_SERVER_FIXTURE_HH_
18 #define _GAZEBO_SERVER_FIXTURE_HH_
20 #pragma GCC diagnostic ignored "-Wswitch-default"
21 #pragma GCC diagnostic ignored "-Wfloat-equal"
22 #pragma GCC diagnostic ignored "-Wshadow"
26 # include <mach/mach.h>
31 #include <gtest/gtest.h>
32 #include <boost/thread.hpp>
34 #include <boost/filesystem.hpp>
40 #include <ignition/math/Pose3.hh>
41 #include <ignition/math/SignalStats.hh>
42 #include <ignition/math/Vector3Stats.hh>
44 #include "gazebo/transport/transport.hh"
52 #include "gazebo/sensors/sensors.hh"
53 #include "gazebo/rendering/rendering.hh"
56 #include "gazebo/gazebo_config.h"
60 #include "test_config.h"
75 protected:
virtual void TearDown();
78 protected:
virtual void Unload();
82 protected:
virtual void Load(
const std::string &_worldFilename);
88 protected:
virtual void Load(
const std::string &_worldFilename,
98 protected:
virtual void Load(
const std::string &_worldFilename,
99 bool _paused,
const std::string &_physics,
100 const std::vector<std::string> &_systemPlugins = {});
106 protected:
virtual void LoadArgs(
const std::string &_args);
112 protected:
void RunServer(
const std::vector<std::string> &_args);
117 const std::string &_sceneName =
"default");
121 protected:
void OnStats(ConstWorldStatisticsPtr &_msg);
124 protected:
void SetPause(
bool _pause);
128 protected:
double GetPercentRealTime()
const;
133 protected:
void OnPose(ConstPosesStampedPtr &_msg);
138 protected: ignition::math::Pose3d EntityPose(
139 const std::string &_name);
144 protected:
bool HasEntity(
const std::string &_name);
152 protected:
void PrintImage(
const std::string &_name,
unsigned char **_image,
153 unsigned int _width,
unsigned int _height,
154 unsigned int _depth);
160 protected:
void PrintScan(
const std::string &_name,
double *_scan,
161 unsigned int _sampleCount);
171 protected:
void FloatCompare(
float *_scanA,
float *_scanB,
172 unsigned int _sampleCount,
float &_diffMax,
173 float &_diffSum,
float &_diffAvg);
183 protected:
void DoubleCompare(
double *_scanA,
double *_scanB,
184 unsigned int _sampleCount,
double &_diffMax,
185 double &_diffSum,
double &_diffAvg);
196 protected:
void ImageCompare(
unsigned char *_imageA,
197 unsigned char *_imageB,
198 unsigned int _width,
unsigned int _height,
200 unsigned int &_diffMax,
unsigned int &_diffSum,
209 private:
void OnNewFrame(
const unsigned char *_image,
210 unsigned int _width,
unsigned int _height,
212 const std::string &);
219 protected:
void GetFrame(
const std::string &_cameraName,
220 unsigned char **_imgData,
unsigned int &_width,
221 unsigned int &_height);
232 protected:
template<
typename T>
235 ASSERT_TRUE(_ptr !=
NULL);
256 protected:
void SpawnCamera(
const std::string &_modelName,
257 const std::string &_cameraName,
258 const ignition::math::Vector3d &_pos =
259 ignition::math::Vector3d::Zero,
260 const ignition::math::Vector3d &_rpy =
261 ignition::math::Vector3d::Zero,
262 unsigned int _width = 320,
unsigned int _height = 240,
264 const std::string &_noiseType =
"",
265 double _noiseMean = 0.0,
double _noiseStdDev = 0.0,
266 bool _distortion =
false,
double _distortionK1 = 0.0,
267 double _distortionK2 = 0.0,
double _distortionK3 = 0.0,
268 double _distortionP1 = 0.0,
double _distortionP2 = 0.0,
269 double _cx = 0.5,
double _cy = 0.5);
294 protected:
void SpawnWideAngleCamera(
const std::string &_modelName,
295 const std::string &_cameraName,
296 const ignition::math::Vector3d &_pos =
297 ignition::math::Vector3d::Zero,
298 const ignition::math::Vector3d &_rpy =
299 ignition::math::Vector3d::Zero,
300 unsigned int _width = 320,
301 unsigned int _height = 240,
303 const double _hfov = 60,
304 const std::string &_lensType =
"stereographic",
305 const bool _scaleToHfov =
true,
306 const double _cutoffAngle = 3.1415,
307 const double _envTextureSize = 512,
308 const double _c1 = 1.05,
const double _c2 = 4,
309 const double _f = 1.0,
310 const std::string &_fun =
"tan");
327 protected:
void SpawnRaySensor(
const std::string &_modelName,
328 const std::string &_raySensorName,
329 const ignition::math::Vector3d &_pos =
330 ignition::math::Vector3d::Zero,
331 const ignition::math::Vector3d &_rpy =
332 ignition::math::Vector3d::Zero,
333 double _hMinAngle = -2.0,
double _hMaxAngle = 2.0,
334 double _vMinAngle = -1.0,
double _vMaxAngle = 1.0,
335 double _minRange = 0.08,
double _maxRange = 10,
336 double _rangeResolution = 0.01,
unsigned int _samples = 640,
337 unsigned int _vSamples = 1,
double _hResolution = 1.0,
338 double _vResolution = 1.0,
339 const std::string &_noiseType =
"",
double _noiseMean = 0.0,
340 double _noiseStdDev = 0.0);
350 const std::string &_sonarName,
351 const ignition::math::Pose3d &_pose,
352 const double _minRange,
353 const double _maxRange,
354 const double _radius);
371 protected:
void SpawnGpuRaySensor(
const std::string &_modelName,
372 const std::string &_raySensorName,
373 const ignition::math::Vector3d &_pos =
374 ignition::math::Vector3d::Zero,
375 const ignition::math::Vector3d &_rpy =
376 ignition::math::Vector3d::Zero,
377 double _hMinAngle = -2.0,
double _hMaxAngle = 2.0,
378 double _minRange = 0.08,
double _maxRange = 10,
379 double _rangeResolution = 0.01,
unsigned int _samples = 640,
380 const std::string &_noiseType =
"",
double _noiseMean = 0.0,
381 double _noiseStdDev = 0.0);
393 protected:
void SpawnDepthCameraSensor(
const std::string &_modelName,
394 const std::string &_cameraName,
395 const ignition::math::Vector3d &_pos =
396 ignition::math::Vector3d::Zero,
397 const ignition::math::Vector3d &_rpy =
398 ignition::math::Vector3d::Zero,
399 const unsigned int _width = 320,
400 const unsigned int _height = 240,
401 const double _rate = 25,
const double _near = 0.1,
402 const double _far = 10);
417 protected:
void SpawnImuSensor(
const std::string &_modelName,
418 const std::string &_imuSensorName,
419 const ignition::math::Vector3d &_pos =
420 ignition::math::Vector3d::Zero,
421 const ignition::math::Vector3d &_rpy =
422 ignition::math::Vector3d::Zero,
423 const std::string &_noiseType =
"",
424 double _rateNoiseMean = 0.0,
double _rateNoiseStdDev = 0.0,
425 double _rateBiasMean = 0.0,
double _rateBiasStdDev = 0.0,
426 double _accelNoiseMean = 0.0,
double _accelNoiseStdDev = 0.0,
427 double _accelBiasMean = 0.0,
double _accelBiasStdDev = 0.0);
436 protected:
void SpawnUnitContactSensor(
const std::string &_name,
437 const std::string &_sensorName,
438 const std::string &_collisionType,
439 const ignition::math::Vector3d &_pos =
440 ignition::math::Vector3d::Zero,
441 const ignition::math::Vector3d &_rpy =
442 ignition::math::Vector3d::Zero,
443 bool _static =
false);
453 protected:
void SpawnUnitImuSensor(
const std::string &_name,
454 const std::string &_sensorName,
455 const std::string &_collisionType,
456 const std::string &_topic,
457 const ignition::math::Vector3d &_pos =
458 ignition::math::Vector3d::Zero,
459 const ignition::math::Vector3d &_rpy =
460 ignition::math::Vector3d::Zero,
461 bool _static =
false);
471 protected:
void SpawnUnitAltimeterSensor(
const std::string &_name,
472 const std::string &_sensorName,
473 const std::string &_collisionType,
474 const std::string &_topic,
475 const ignition::math::Vector3d &_pos =
476 ignition::math::Vector3d::Zero,
477 const ignition::math::Vector3d &_rpy =
478 ignition::math::Vector3d::Zero,
479 bool _static =
false);
489 protected:
void SpawnUnitMagnetometerSensor(
const std::string &_name,
490 const std::string &_sensorName,
491 const std::string &_collisionType,
492 const std::string &_topic,
493 const ignition::math::Vector3d &_pos =
494 ignition::math::Vector3d::Zero,
495 const ignition::math::Vector3d &_rpy =
496 ignition::math::Vector3d::Zero,
497 bool _static =
false);
503 private:
void launchTimeoutFailure(
const char *_logMsg,
504 const int _timeoutCS);
516 protected:
void SpawnWirelessTransmitterSensor(
const std::string &_name,
517 const std::string &_sensorName,
518 const ignition::math::Vector3d &_pos,
519 const ignition::math::Vector3d &_rpy,
520 const std::string &_essid,
524 bool _visualize =
true);
537 protected:
void SpawnWirelessReceiverSensor(
const std::string &_name,
538 const std::string &_sensorName,
539 const ignition::math::Vector3d &_pos,
540 const ignition::math::Vector3d &_rpy,
546 bool _visualize =
true);
552 protected:
void WaitUntilEntitySpawn(
const std::string &_name,
553 unsigned int _sleepEach,
560 protected:
void WaitUntilSensorSpawn(
const std::string &_name,
561 unsigned int _sleepEach,
569 protected:
void WaitUntilIteration(
const uint32_t _goalIteration,
570 const int _sleepEach,
571 const int _retries)
const;
578 protected:
void WaitUntilSimTime(
const common::Time &_goalTime,
580 const int _maxRetries)
const;
599 protected:
void SpawnLight(
const std::string &_name,
600 const std::string &_type,
601 const ignition::math::Vector3d &_pos,
602 const ignition::math::Vector3d &_rpy,
605 const ignition::math::Vector3d &_direction =
606 -ignition::math::Vector3d::UnitZ,
607 double _attenuationRange = 20,
608 double _attenuationConstant = 0.5,
609 double _attenuationLinear = 0.01,
610 double _attenuationQuadratic = 0.001,
611 double _spotInnerAngle = 0,
612 double _spotOuterAngle = 0,
613 double _spotFallOff = 0,
632 protected:
void SpawnLight(const std::
string &_name,
633 const std::
string &_type,
634 const ignition::math::Vector3d &_pos =
635 ignition::math::Vector3d::Zero,
636 const ignition::math::Vector3d &_rpy =
637 ignition::math::Vector3d::Zero,
638 const ignition::math::Color &_diffuse =
639 ignition::math::Color::White,
640 const ignition::math::Color &_specular =
641 ignition::math::Color::White,
642 const ignition::math::Vector3d &_direction =
643 -ignition::math::Vector3d::UnitZ,
644 const
double _attenuationRange = 20,
645 const
double _attenuationConstant = 0.5,
646 const
double _attenuationLinear = 0.01,
647 const
double _attenuationQuadratic = 0.001,
648 const
double _spotInnerAngle = 0,
649 const
double _spotOuterAngle = 0,
650 const
double _spotFallOff = 0,
651 const
bool _castShadows = true);
658 protected:
void SpawnCylinder(const std::
string &_name,
659 const ignition::math::Vector3d &_pos =
660 ignition::math::Vector3d::Zero,
661 const ignition::math::Vector3d &_rpy =
662 ignition::math::Vector3d::Zero,
663 bool _static = false);
672 protected:
void SpawnSphere(const std::
string &_name,
673 const ignition::math::Vector3d &_pos,
674 const ignition::math::Vector3d &_rpy,
675 bool _wait = true,
bool _static = false);
686 protected:
void SpawnSphere(const std::
string &_name,
687 const ignition::math::Vector3d &_pos,
688 const ignition::math::Vector3d &_rpy,
689 const ignition::math::Vector3d &_cog,
690 double _radius = 1.0,
691 bool _wait = true,
bool _static = false);
699 protected:
void SpawnBox(const std::
string &_name,
700 const ignition::math::Vector3d &_size =
701 ignition::math::Vector3d::One,
702 const ignition::math::Vector3d &_pos =
703 ignition::math::Vector3d::Zero,
704 const ignition::math::Vector3d &_rpy =
705 ignition::math::Vector3d::Zero,
706 bool _static = false);
715 protected:
void SpawnTrimesh(const std::
string &_name,
716 const std::
string &_modelPath,
717 const ignition::math::Vector3d &_scale =
718 ignition::math::Vector3d::One,
719 const ignition::math::Vector3d &_pos =
720 ignition::math::Vector3d::Zero,
721 const ignition::math::Vector3d &_rpy =
722 ignition::math::Vector3d::Zero,
723 bool _static = false);
730 protected:
void SpawnEmptyLink(const std::
string &_name,
731 const ignition::math::Vector3d &_pos =
732 ignition::math::Vector3d::Zero,
733 const ignition::math::Vector3d &_rpy =
734 ignition::math::Vector3d::Zero,
735 bool _static = false);
739 protected:
void SpawnModel(const std::
string &_filename);
743 protected:
void SpawnSDF(const std::
string &_sdf);
748 protected:
void LoadPlugin(const std::
string &_filename,
749 const std::
string &_name);
754 protected: physics::
ModelPtr GetModel(const std::
string &_name);
758 protected:
void RemoveModel(const std::
string &_name);
762 protected:
void RemovePlugin(const std::
string &_name);
767 protected:
void GetMemInfo(
double &_resident,
double &_share);
772 protected: std::
string GetUniqueString(const std::
string &_prefix);
777 protected:
void Record(const std::
string &_name, const
double _data);
782 protected:
void Record(const std::
string &_prefix,
783 const ignition::math::SignalStats &_stats);
788 protected:
void Record(const std::
string &_prefix,
789 const ignition::math::Vector3Stats &_stats);
795 protected: boost::thread *serverThread;
813 protected: std::map<std::
string, ignition::math::Pose3d> poses;
816 protected: std::mutex receiveMutex;
819 private:
unsigned char **imgData;
822 private:
int gotImage;
825 protected: common::Time simTime, realTime, pauseTime;
828 private:
double percentRealTime;
831 private:
bool paused;
834 private:
bool serverRunning;
837 private:
int uniqueCounter;
843 public:
virtual void SetUp();
846 protected:
virtual void Unload();
849 #endif // define _GAZEBO_SERVER_FIXTURE_HH_
static const Color White
(1, 1, 1)
Definition: Color.hh:39
Definition: ServerFixture.hh:66
std::string custom_exec(std::string _cmd)
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
default namespace for gazebo
Definition: ServerFixture.hh:840
boost::shared_ptr< Scene > ScenePtr
Definition: RenderTypes.hh:82
static void CheckPointer(boost::shared_ptr< T > _ptr)
Check that a pointer is not NULL.
Definition: ServerFixture.hh:233
#define NULL
Definition: CommonTypes.hh:31
Defines a color.
Definition: Color.hh:36
#define GAZEBO_DEPRECATED(version)
Definition: system.hh:328
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:93
std::shared_ptr< SonarSensor > SonarSensorPtr
Definition: SensorTypes.hh:112
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:59
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:44