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>
33 #include <boost/filesystem.hpp>
39 #include "gazebo/transport/transport.hh"
47 #include "gazebo/sensors/sensors.hh"
48 #include "gazebo/rendering/rendering.hh"
54 #include "gazebo/gazebo_config.h"
58 #include "test_config.h"
73 protected:
virtual void TearDown();
76 protected:
virtual void Unload();
80 protected:
virtual void Load(
const std::string &_worldFilename);
86 protected:
virtual void Load(
const std::string &_worldFilename,
96 protected:
virtual void Load(
const std::string &_worldFilename,
97 bool _paused,
const std::string &_physics,
98 const std::vector<std::string> &_systemPlugins = {});
102 protected:
void RunServer(
const std::string &_worldFilename);
110 protected:
void RunServer(
const std::string &_worldFilename,
bool _paused,
111 const std::string &_physics,
112 const std::vector<std::string> &_systemPlugins = {});
118 const std::string &_sceneName =
"default");
123 protected:
void OnStats(ConstWorldStatisticsPtr &_msg);
126 protected:
void SetPause(
bool _pause);
130 protected:
double GetPercentRealTime()
const;
135 protected:
void OnPose(ConstPosesStampedPtr &_msg);
140 protected:
math::Pose GetEntityPose(
const std::string &_name);
145 protected:
bool HasEntity(
const std::string &_name);
153 protected:
void PrintImage(
const std::string &_name,
unsigned char **_image,
154 unsigned int _width,
unsigned int _height,
155 unsigned int _depth);
161 protected:
void PrintScan(
const std::string &_name,
double *_scan,
162 unsigned int _sampleCount);
172 protected:
void FloatCompare(
float *_scanA,
float *_scanB,
173 unsigned int _sampleCount,
float &_diffMax,
174 float &_diffSum,
float &_diffAvg);
184 protected:
void DoubleCompare(
double *_scanA,
double *_scanB,
185 unsigned int _sampleCount,
double &_diffMax,
186 double &_diffSum,
double &_diffAvg);
197 protected:
void ImageCompare(
unsigned char *_imageA,
198 unsigned char *_imageB,
199 unsigned int _width,
unsigned int _height,
201 unsigned int &_diffMax,
unsigned int &_diffSum,
210 private:
void OnNewFrame(
const unsigned char *_image,
211 unsigned int _width,
unsigned int _height,
213 const std::string &);
220 protected:
void GetFrame(
const std::string &_cameraName,
221 unsigned char **_imgData,
unsigned int &_width,
222 unsigned int &_height);
233 protected:
template<
typename T>
236 ASSERT_TRUE(_ptr !=
NULL);
257 protected:
void SpawnCamera(
const std::string &_modelName,
258 const std::string &_cameraName,
260 unsigned int _width = 320,
unsigned int _height = 240,
262 const std::string &_noiseType =
"",
263 double _noiseMean = 0.0,
double _noiseStdDev = 0.0,
264 bool _distortion =
false,
double _distortionK1 = 0.0,
265 double _distortionK2 = 0.0,
double _distortionK3 = 0.0,
266 double _distortionP1 = 0.0,
double _distortionP2 = 0.0,
267 double _cx = 0.5,
double _cy = 0.5);
284 protected:
void SpawnRaySensor(
const std::string &_modelName,
285 const std::string &_raySensorName,
287 double _hMinAngle = -2.0,
double _hMaxAngle = 2.0,
288 double _vMinAngle = -1.0,
double _vMaxAngle = 1.0,
289 double _minRange = 0.08,
double _maxRange = 10,
290 double _rangeResolution = 0.01,
unsigned int _samples = 640,
291 unsigned int _vSamples = 1,
double _hResolution = 1.0,
292 double _vResolution = 1.0,
293 const std::string &_noiseType =
"",
double _noiseMean = 0.0,
294 double _noiseStdDev = 0.0);
311 protected:
void SpawnGpuRaySensor(
const std::string &_modelName,
312 const std::string &_raySensorName,
314 double _hMinAngle = -2.0,
double _hMaxAngle = 2.0,
315 double _minRange = 0.08,
double _maxRange = 10,
316 double _rangeResolution = 0.01,
unsigned int _samples = 640,
317 const std::string &_noiseType =
"",
double _noiseMean = 0.0,
318 double _noiseStdDev = 0.0);
333 protected:
void SpawnImuSensor(
const std::string &_modelName,
334 const std::string &_imuSensorName,
336 const std::string &_noiseType =
"",
337 double _rateNoiseMean = 0.0,
double _rateNoiseStdDev = 0.0,
338 double _rateBiasMean = 0.0,
double _rateBiasStdDev = 0.0,
339 double _accelNoiseMean = 0.0,
double _accelNoiseStdDev = 0.0,
340 double _accelBiasMean = 0.0,
double _accelBiasStdDev = 0.0);
349 protected:
void SpawnUnitContactSensor(
const std::string &_name,
350 const std::string &_sensorName,
351 const std::string &_collisionType,
const math::Vector3 &_pos,
362 protected:
void SpawnUnitImuSensor(
const std::string &_name,
363 const std::string &_sensorName,
364 const std::string &_collisionType,
376 protected:
void SpawnUnitAltimeterSensor(
const std::string &_name,
377 const std::string &_sensorName,
378 const std::string &_collisionType,
379 const std::string &_topic,
380 const ignition::math::Vector3d &_pos,
381 const ignition::math::Vector3d &_rpy,
382 bool _static =
false);
392 protected:
void SpawnUnitMagnetometerSensor(
const std::string &_name,
393 const std::string &_sensorName,
394 const std::string &_collisionType,
395 const std::string &_topic,
396 const ignition::math::Vector3d &_pos,
397 const ignition::math::Vector3d &_rpy,
398 bool _static =
false);
404 private:
void launchTimeoutFailure(
const char *_logMsg,
405 const int _timeoutCS);
417 protected:
void SpawnWirelessTransmitterSensor(
const std::string &_name,
418 const std::string &_sensorName,
421 const std::string &_essid,
425 bool _visualize =
true);
438 protected:
void SpawnWirelessReceiverSensor(
const std::string &_name,
439 const std::string &_sensorName,
447 bool _visualize =
true);
453 protected:
void WaitUntilEntitySpawn(
const std::string &_name,
454 unsigned int _sleepEach,
461 protected:
void WaitUntilSensorSpawn(
const std::string &_name,
462 unsigned int _sleepEach,
481 protected:
void SpawnLight(
const std::string &_name,
482 const std::string &_type,
487 double _attenuationRange = 20,
488 double _attenuationConstant = 0.5,
489 double _attenuationLinear = 0.01,
490 double _attenuationQuadratic = 0.001,
491 double _spotInnerAngle = 0,
492 double _spotOuterAngle = 0,
493 double _spotFallOff = 0,
494 bool _castShadows =
true);
501 protected:
void SpawnCylinder(
const std::string &_name,
503 bool _static =
false);
512 protected:
void SpawnSphere(
const std::string &_name,
514 bool _wait =
true,
bool _static =
false);
525 protected:
void SpawnSphere(
const std::string &_name,
528 bool _wait =
true,
bool _static =
false);
536 protected:
void SpawnBox(
const std::string &_name,
547 protected:
void SpawnTrimesh(
const std::string &_name,
550 bool _static =
false);
557 protected:
void SpawnEmptyLink(
const std::string &_name,
559 bool _static =
false);
563 protected:
void SpawnModel(
const std::string &_filename);
567 protected:
void SpawnSDF(
const std::string &_sdf);
572 protected:
void LoadPlugin(
const std::string &_filename,
573 const std::string &_name);
582 protected:
void RemoveModel(
const std::string &_name);
586 protected:
void RemovePlugin(
const std::string &_name);
591 protected:
void GetMemInfo(
double &_resident,
double &_share);
596 protected: std::string GetUniqueString(
const std::string &_prefix);
601 protected:
void Record(
const std::string &_name,
const double _data);
606 protected:
void Record(
const std::string &_prefix,
612 protected:
void Record(
const std::string &_prefix,
637 protected: std::map<std::string, math::Pose>
poses;
643 private:
unsigned char **imgData;
646 private:
int gotImage;
652 private:
double percentRealTime;
655 private:
bool paused;
658 private:
bool serverRunning;
661 private:
int uniqueCounter;
664 #endif // define _GAZEBO_SERVER_FIXTURE_HH_
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:84
static const Vector3 UnitZ
math::Vector3(0, 0, 1)
Definition: Vector3.hh:54
static const Color White
(1, 1, 1)
Definition: Color.hh:39
Encapsulates a position and rotation in three space.
Definition: Pose.hh:37
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:39
Definition: ServerFixture.hh:64
boost::thread * serverThread
Pointer the thread the runs the server.
Definition: ServerFixture.hh:619
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
boost::mutex receiveMutex
Mutex to protect data structures that store messages.
Definition: ServerFixture.hh:640
std::string custom_exec(std::string _cmd)
Server * server
Pointer the Gazebo server.
Definition: ServerFixture.hh:616
Collection of statistics for a scalar signal.
Definition: SignalStats.hh:124
Collection of statistics for a Vector3 signal.
Definition: Vector3Stats.hh:37
default namespace for gazebo
transport::NodePtr node
Pointer to a node for communication.
Definition: ServerFixture.hh:622
static void CheckPointer(boost::shared_ptr< T > _ptr)
Check that a pointer is not NULL.
Definition: ServerFixture.hh:234
transport::PublisherPtr factoryPub
Factory publisher.
Definition: ServerFixture.hh:631
#define NULL
Definition: CommonTypes.hh:30
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
Defines a color.
Definition: Color.hh:36
boost::shared_ptr< Scene > ScenePtr
Definition: RenderTypes.hh:79
common::Time simTime
Current simulation time, real time, and pause time.
Definition: ServerFixture.hh:649
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
std::map< std::string, math::Pose > poses
Map of received poses.
Definition: ServerFixture.hh:637
transport::PublisherPtr requestPub
Request publisher.
Definition: ServerFixture.hh:634
transport::SubscriberPtr poseSub
Pose subscription.
Definition: ServerFixture.hh:625
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:66
transport::SubscriberPtr statsSub
World statistics subscription.
Definition: ServerFixture.hh:628
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:39