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 <ignition/math/Pose3.hh>    41 #include "gazebo/transport/transport.hh"    49 #include "gazebo/sensors/sensors.hh"    50 #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: 
math::Pose GetEntityPose(
const std::string &_name);
   143     protected: 
bool HasEntity(
const std::string &_name);
   151     protected: 
void PrintImage(
const std::string &_name, 
unsigned char **_image,
   152                   unsigned int _width, 
unsigned int _height,
   153                   unsigned int _depth);
   159     protected: 
void PrintScan(
const std::string &_name, 
double *_scan,
   160                               unsigned int _sampleCount);
   170     protected: 
void FloatCompare(
float *_scanA, 
float *_scanB,
   171                    unsigned int _sampleCount, 
float &_diffMax,
   172                    float &_diffSum, 
float &_diffAvg);
   182     protected: 
void DoubleCompare(
double *_scanA, 
double *_scanB,
   183                    unsigned int _sampleCount, 
double &_diffMax,
   184                    double &_diffSum, 
double &_diffAvg);
   195     protected: 
void ImageCompare(
unsigned char *_imageA,
   196                    unsigned char *_imageB,
   197                    unsigned int _width, 
unsigned int _height,
   199                    unsigned int &_diffMax, 
unsigned int &_diffSum,
   208     private: 
void OnNewFrame(
const unsigned char *_image,
   209                              unsigned int _width, 
unsigned int _height,
   211                              const std::string &);
   218     protected: 
void GetFrame(
const std::string &_cameraName,
   219                    unsigned char **_imgData, 
unsigned int &_width,
   220                    unsigned int &_height);
   231     protected: 
template<
typename T>
   234         ASSERT_TRUE(_ptr != 
NULL);
   255     protected: 
void SpawnCamera(
const std::string &_modelName,
   256                    const std::string &_cameraName,
   258                    unsigned int _width = 320, 
unsigned int _height = 240,
   260                    const std::string &_noiseType = 
"",
   261                    double _noiseMean = 0.0, 
double _noiseStdDev = 0.0,
   262                    bool _distortion = 
false, 
double _distortionK1 = 0.0,
   263                    double _distortionK2 = 0.0, 
double _distortionK3 = 0.0,
   264                    double _distortionP1 = 0.0, 
double _distortionP2 = 0.0,
   265                    double _cx = 0.5, 
double _cy = 0.5);
   282     protected: 
void SpawnRaySensor(
const std::string &_modelName,
   283                    const std::string &_raySensorName,
   285                    double _hMinAngle = -2.0, 
double _hMaxAngle = 2.0,
   286                    double _vMinAngle = -1.0, 
double _vMaxAngle = 1.0,
   287                    double _minRange = 0.08, 
double _maxRange = 10,
   288                    double _rangeResolution = 0.01, 
unsigned int _samples = 640,
   289                    unsigned int _vSamples = 1, 
double _hResolution = 1.0,
   290                    double _vResolution = 1.0,
   291                    const std::string &_noiseType = 
"", 
double _noiseMean = 0.0,
   292                    double _noiseStdDev = 0.0);
   302                    const std::string &_sonarName,
   303                    const ignition::math::Pose3d &_pose,
   304                    const double _minRange,
   305                    const double _maxRange,
   306                    const double _radius);
   323     protected: 
void SpawnGpuRaySensor(
const std::string &_modelName,
   324                    const std::string &_raySensorName,
   326                    double _hMinAngle = -2.0, 
double _hMaxAngle = 2.0,
   327                    double _minRange = 0.08, 
double _maxRange = 10,
   328                    double _rangeResolution = 0.01, 
unsigned int _samples = 640,
   329                    const std::string &_noiseType = 
"", 
double _noiseMean = 0.0,
   330                    double _noiseStdDev = 0.0);
   345     protected: 
void SpawnImuSensor(
const std::string &_modelName,
   346                    const std::string &_imuSensorName,
   348                    const std::string &_noiseType = 
"",
   349                    double _rateNoiseMean = 0.0, 
double _rateNoiseStdDev = 0.0,
   350                    double _rateBiasMean = 0.0, 
double _rateBiasStdDev = 0.0,
   351                    double _accelNoiseMean = 0.0, 
double _accelNoiseStdDev = 0.0,
   352                    double _accelBiasMean = 0.0, 
double _accelBiasStdDev = 0.0);
   361     protected: 
void SpawnUnitContactSensor(
const std::string &_name,
   362                    const std::string &_sensorName,
   363                    const std::string &_collisionType, 
const math::Vector3 &_pos,
   374     protected: 
void SpawnUnitImuSensor(
const std::string &_name,
   375                    const std::string &_sensorName,
   376                    const std::string &_collisionType,
   388     protected: 
void SpawnUnitAltimeterSensor(
const std::string &_name,
   389                    const std::string &_sensorName,
   390                    const std::string &_collisionType,
   391                    const std::string &_topic,
   392                    const ignition::math::Vector3d &_pos,
   393                    const ignition::math::Vector3d &_rpy,
   394                    bool _static = 
false);
   404     protected: 
void SpawnUnitMagnetometerSensor(
const std::string &_name,
   405                    const std::string &_sensorName,
   406                    const std::string &_collisionType,
   407                    const std::string &_topic,
   408                    const ignition::math::Vector3d &_pos,
   409                    const ignition::math::Vector3d &_rpy,
   410                    bool _static = 
false);
   416     private: 
void launchTimeoutFailure(
const char *_logMsg,
   417                                        const int _timeoutCS);
   429     protected: 
void SpawnWirelessTransmitterSensor(
const std::string &_name,
   430                    const std::string &_sensorName,
   433                    const std::string &_essid,
   437                    bool _visualize = 
true);
   450     protected: 
void SpawnWirelessReceiverSensor(
const std::string &_name,
   451                    const std::string &_sensorName,
   459                    bool _visualize = 
true);
   465     protected: 
void WaitUntilEntitySpawn(
const std::string &_name,
   466                                        unsigned int _sleepEach,
   473     protected: 
void WaitUntilSensorSpawn(
const std::string &_name,
   474                                          unsigned int _sleepEach,
   482     protected: 
void WaitUntilIteration(
const uint32_t _goalIteration,
   483                                        const int _sleepEach,
   484                                        const int _retries) 
const;
   491     protected: 
void WaitUntilSimTime(
const common::Time &_goalTime,
   493                                      const int _maxRetries) 
const;
   511     protected: 
void SpawnLight(
const std::string &_name,
   512                    const std::string &_type,
   517                    double _attenuationRange = 20,
   518                    double _attenuationConstant = 0.5,
   519                    double _attenuationLinear = 0.01,
   520                    double _attenuationQuadratic = 0.001,
   521                    double _spotInnerAngle = 0,
   522                    double _spotOuterAngle = 0,
   523                    double _spotFallOff = 0,
   524                    bool _castShadows = 
true);
   531     protected: 
void SpawnCylinder(
const std::string &_name,
   533                    bool _static = 
false);
   542     protected: 
void SpawnSphere(
const std::string &_name,
   544                    bool _wait = 
true, 
bool _static = 
false);
   555     protected: 
void SpawnSphere(
const std::string &_name,
   558                    bool _wait = 
true, 
bool _static = 
false);
   566     protected: 
void SpawnBox(
const std::string &_name,
   577     protected: 
void SpawnTrimesh(
const std::string &_name,
   580                    bool _static = 
false);
   587     protected: 
void SpawnEmptyLink(
const std::string &_name,
   589                    bool _static = 
false);
   593     protected: 
void SpawnModel(
const std::string &_filename);
   597     protected: 
void SpawnSDF(
const std::string &_sdf);
   602     protected: 
void LoadPlugin(
const std::string &_filename,
   603                                const std::string &_name);
   612     protected: 
void RemoveModel(
const std::string &_name);
   616     protected: 
void RemovePlugin(
const std::string &_name);
   621     protected: 
void GetMemInfo(
double &_resident, 
double &_share);
   626     protected: std::string GetUniqueString(
const std::string &_prefix);
   631     protected: 
void Record(
const std::string &_name, 
const double _data);
   636     protected: 
void Record(
const std::string &_prefix,
   642     protected: 
void Record(
const std::string &_prefix,
   667     protected: std::map<std::string, math::Pose> 
poses;
   673     private: 
unsigned char **imgData;
   676     private: 
int gotImage;
   682     private: 
double percentRealTime;
   685     private: 
bool paused;
   688     private: 
bool serverRunning;
   691     private: 
int uniqueCounter;
   697     public: 
virtual void SetUp();
   700 #endif  // define _GAZEBO_SERVER_FIXTURE_HH_ boost::mutex receiveMutex
Mutex to protect data structures that store messages. 
Definition: ServerFixture.hh:670
 
transport::SubscriberPtr statsSub
World statistics subscription. 
Definition: ServerFixture.hh:658
 
static const Color White
(1, 1, 1) 
Definition: Color.hh:39
 
transport::SubscriberPtr poseSub
Pose subscription. 
Definition: ServerFixture.hh:655
 
Forward declarations for the common classes. 
Definition: Animation.hh:33
 
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:66
 
std::string custom_exec(std::string _cmd)
 
transport::PublisherPtr factoryPub
Factory publisher. 
Definition: ServerFixture.hh:661
 
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
 
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
 
Collection of statistics for a scalar signal. 
Definition: SignalStats.hh:124
 
boost::thread * serverThread
Pointer the thread the runs the server. 
Definition: ServerFixture.hh:649
 
Collection of statistics for a Vector3 signal. 
Definition: Vector3Stats.hh:37
 
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:652
 
Definition: ServerFixture.hh:694
 
boost::shared_ptr< Scene > ScenePtr
Definition: RenderTypes.hh:80
 
common::Time simTime
Current simulation time, real time, and pause time. 
Definition: ServerFixture.hh:679
 
static const Vector3 UnitZ
math::Vector3(0, 0, 1) 
Definition: Vector3.hh:54
 
static void CheckPointer(boost::shared_ptr< T > _ptr)
Check that a pointer is not NULL. 
Definition: ServerFixture.hh:232
 
#define NULL
Definition: CommonTypes.hh:31
 
Defines a color. 
Definition: Color.hh:36
 
transport::PublisherPtr requestPub
Request publisher. 
Definition: ServerFixture.hh:664
 
Server * server
Pointer the Gazebo server. 
Definition: ServerFixture.hh:646
 
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:88
 
std::map< std::string, math::Pose > poses
Map of received poses. 
Definition: ServerFixture.hh:667
 
std::shared_ptr< SonarSensor > SonarSensorPtr
Definition: SensorTypes.hh:107
 
#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