diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 2af51455e2..47cee013a6 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -485,7 +485,7 @@ const AP_Param::Info Rover::var_info[] PROGMEM = { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL // @Group: SIM_ // @Path: ../libraries/SITL/SITL.cpp - GOBJECT(sitl, "SIM_", SITL), + GOBJECT(sitl, "SIM_", SITL::SITL), #endif // @Group: AHRS_ diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index dac01e27f2..197c3ef84e 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -169,7 +169,7 @@ private: AP_RSSI rssi; #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - SITL sitl; + SITL::SITL sitl; #endif // GCS handling diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 47f6c5f868..cdd293b2e8 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -241,7 +241,7 @@ const AP_Param::Info Tracker::var_info[] PROGMEM = { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL // @Group: SIM_ // @Path: ../libraries/SITL/SITL.cpp - GOBJECT(sitl, "SIM_", SITL), + GOBJECT(sitl, "SIM_", SITL::SITL), #endif // @Group: BRD_ diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index c4a198575e..4e3fcf1761 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -122,7 +122,7 @@ private: #endif #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - SITL sitl; + SITL::SITL sitl; #endif /** diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 1964845338..710918b292 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -186,7 +186,7 @@ private: AP_AHRS_NavEKF ahrs{ins, barometer, gps, sonar, EKF, EKF2, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF}; #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - SITL sitl; + SITL::SITL sitl; #endif // Mission library diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index e748410650..6504d883f7 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -974,7 +974,7 @@ const AP_Param::Info Copter::var_info[] PROGMEM = { #endif #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - GOBJECT(sitl, "SIM_", SITL), + GOBJECT(sitl, "SIM_", SITL::SITL), #endif // @Group: GND_ diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 1323533549..c7e257fded 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1161,7 +1161,7 @@ const AP_Param::Info Plane::var_info[] PROGMEM = { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL // @Group: SIM_ // @Path: ../libraries/SITL/SITL.cpp - GOBJECT(sitl, "SIM_", SITL), + GOBJECT(sitl, "SIM_", SITL::SITL), #endif #if OBC_FAILSAFE == ENABLED diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 0ed566c95b..31f6779263 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -224,7 +224,7 @@ private: AP_SteerController steerController {ahrs}; #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - SITL sitl; + SITL::SITL sitl; #endif // Training mode diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index 54e592aafc..25b236ce16 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -230,7 +230,7 @@ private: ReplayVehicle &_vehicle; #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - SITL sitl; + SITL::SITL sitl; #endif LogReader logreader{_vehicle.ahrs, _vehicle.ins, _vehicle.barometer, _vehicle.compass, _vehicle.gps, _vehicle.airspeed, _vehicle.dataflash, log_structure, ARRAY_SIZE(log_structure), nottypes}; diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index eaa0174b3c..c3c4e9d831 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -22,6 +22,7 @@ extern const AP_HAL::HAL& hal; using namespace HALSITL; +using namespace SITL; void SITL_State::_set_param_default(const char *parm) { @@ -74,7 +75,7 @@ void SITL_State::_sitl_setup(void) fprintf(stdout, "Starting SITL input\n"); // find the barometer object if it exists - _sitl = (SITL *)AP_Param::find_object("SIM_"); + _sitl = (SITL::SITL *)AP_Param::find_object("SIM_"); _barometer = (AP_Baro *)AP_Param::find_object("GND_"); _ins = (AP_InertialSensor *)AP_Param::find_object("INS_"); _compass = (Compass *)AP_Param::find_object("COMPASS_"); diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index 3556cbce21..d56fec7ff6 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -109,7 +109,7 @@ private: float airspeed, float altitude); void _fdm_input(void); void _fdm_input_local(void); - void _simulator_servos(Aircraft::sitl_input &input); + void _simulator_servos(SITL::Aircraft::sitl_input &input); void _simulator_output(bool synthetic_clock_mode); void _apply_servo_filter(float deltat); uint16_t _airspeed_sensor(float airspeed); @@ -142,7 +142,7 @@ private: AP_Terrain *_terrain; int _sitl_fd; - SITL *_sitl; + SITL::SITL *_sitl; uint16_t _rcout_port; uint16_t _simin_port; float _current; @@ -190,11 +190,11 @@ private: uint32_t delayed_time_baro; // internal SITL model - Aircraft *sitl_model; + SITL::Aircraft *sitl_model; // simulated gimbal bool enable_gimbal; - Gimbal *gimbal; + SITL::Gimbal *gimbal; // TCP address to connect uartC to const char *_client_address; diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index a449c13676..09e5054b4b 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -26,6 +26,7 @@ extern const AP_HAL::HAL& hal; using namespace HALSITL; +using namespace SITL; // catch floating point exceptions static void _sig_fpe(int signum) diff --git a/libraries/AP_HAL_SITL/sitl_gps.cpp b/libraries/AP_HAL_SITL/sitl_gps.cpp index 039b456960..3e7d91c847 100644 --- a/libraries/AP_HAL_SITL/sitl_gps.cpp +++ b/libraries/AP_HAL_SITL/sitl_gps.cpp @@ -801,36 +801,36 @@ void SITL_State::_update_gps(double latitude, double longitude, float altitude, return; } - switch ((SITL::GPSType)_sitl->gps_type.get()) { - case SITL::GPS_TYPE_NONE: + switch ((SITL::SITL::GPSType)_sitl->gps_type.get()) { + case SITL::SITL::GPS_TYPE_NONE: // no GPS attached break; - case SITL::GPS_TYPE_UBLOX: + case SITL::SITL::GPS_TYPE_UBLOX: _update_gps_ubx(&d); break; - case SITL::GPS_TYPE_MTK: + case SITL::SITL::GPS_TYPE_MTK: _update_gps_mtk(&d); break; - case SITL::GPS_TYPE_MTK16: + case SITL::SITL::GPS_TYPE_MTK16: _update_gps_mtk16(&d); break; - case SITL::GPS_TYPE_MTK19: + case SITL::SITL::GPS_TYPE_MTK19: _update_gps_mtk19(&d); break; - case SITL::GPS_TYPE_NMEA: + case SITL::SITL::GPS_TYPE_NMEA: _update_gps_nmea(&d); break; - case SITL::GPS_TYPE_SBP: + case SITL::SITL::GPS_TYPE_SBP: _update_gps_sbp(&d); break; - case SITL::GPS_TYPE_FILE: + case SITL::SITL::GPS_TYPE_FILE: _update_gps_file(&d); break; diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index a2b95a1728..1f684862c9 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -30,6 +30,8 @@ #include #endif +namespace SITL { + /* parent class for all simulator types */ @@ -290,4 +292,7 @@ void Aircraft::set_speedup(float speedup) { setup_frame_time(rate_hz, speedup); } + +} // namespace SITL + #endif // CONFIG_HAL_BOARD diff --git a/libraries/SITL/SIM_Aircraft.h b/libraries/SITL/SIM_Aircraft.h index f029b973f7..fb3f6c2863 100644 --- a/libraries/SITL/SIM_Aircraft.h +++ b/libraries/SITL/SIM_Aircraft.h @@ -24,6 +24,8 @@ #include #include +namespace SITL { + /* parent class for all simulator types */ @@ -136,5 +138,7 @@ private: const uint32_t min_sleep_time; }; +} // namespace SITL + #endif // _SIM_AIRCRAFT_H diff --git a/libraries/SITL/SIM_Balloon.cpp b/libraries/SITL/SIM_Balloon.cpp index 9fe58cfe30..2fe182de2b 100644 --- a/libraries/SITL/SIM_Balloon.cpp +++ b/libraries/SITL/SIM_Balloon.cpp @@ -22,6 +22,8 @@ #include "SIM_Balloon.h" #include +namespace SITL { + /* constructor */ @@ -119,4 +121,7 @@ void Balloon::update(const struct sitl_input &input) // update lat/lon/altitude update_position(); } + +} // namespace SITL + #endif // CONFIG_HAL_BOARD diff --git a/libraries/SITL/SIM_Balloon.h b/libraries/SITL/SIM_Balloon.h index 8d58643198..7a41a21714 100644 --- a/libraries/SITL/SIM_Balloon.h +++ b/libraries/SITL/SIM_Balloon.h @@ -22,6 +22,8 @@ #include "SIM_Aircraft.h" +namespace SITL { + /* a balloon simulator */ @@ -47,5 +49,6 @@ private: bool released = false; }; +} // namespace SITL #endif // _SIM_BALLOON_H diff --git a/libraries/SITL/SIM_CRRCSim.cpp b/libraries/SITL/SIM_CRRCSim.cpp index f3a910de6d..e0b73dd5b6 100644 --- a/libraries/SITL/SIM_CRRCSim.cpp +++ b/libraries/SITL/SIM_CRRCSim.cpp @@ -24,6 +24,8 @@ extern const AP_HAL::HAL& hal; +namespace SITL { + /* constructor */ @@ -152,4 +154,7 @@ void CRRCSim::update(const struct sitl_input &input) recv_fdm(input); update_position(); } + +} // namespace SITL + #endif // CONFIG_HAL_BOARD diff --git a/libraries/SITL/SIM_CRRCSim.h b/libraries/SITL/SIM_CRRCSim.h index 663701c4ae..be0caa2797 100644 --- a/libraries/SITL/SIM_CRRCSim.h +++ b/libraries/SITL/SIM_CRRCSim.h @@ -23,6 +23,8 @@ #include "SIM_Aircraft.h" #include +namespace SITL { + /* a CRRCSim simulator */ @@ -76,5 +78,6 @@ private: SocketAPM sock; }; +} // namespace SITL #endif // _SIM_CRRCSIM_H diff --git a/libraries/SITL/SIM_Gazebo.cpp b/libraries/SITL/SIM_Gazebo.cpp index 353b4d73ca..a02609dcf6 100644 --- a/libraries/SITL/SIM_Gazebo.cpp +++ b/libraries/SITL/SIM_Gazebo.cpp @@ -24,6 +24,8 @@ extern const AP_HAL::HAL& hal; +namespace SITL { + /* constructor */ @@ -127,4 +129,7 @@ void Gazebo::update(const struct sitl_input &input) recv_fdm(input); update_position(); } + +} // namespace SITL + #endif // CONFIG_HAL_BOARD diff --git a/libraries/SITL/SIM_Gazebo.h b/libraries/SITL/SIM_Gazebo.h index 7b64bc96bc..120cff8ea5 100644 --- a/libraries/SITL/SIM_Gazebo.h +++ b/libraries/SITL/SIM_Gazebo.h @@ -23,6 +23,8 @@ #include "SIM_Aircraft.h" #include +namespace SITL { + /* Gazebo simulator */ @@ -68,5 +70,6 @@ private: SocketAPM sock; }; +} // namespace SITL #endif // _SIM_GAZEBO_H diff --git a/libraries/SITL/SIM_Gimbal.cpp b/libraries/SITL/SIM_Gimbal.cpp index 789413ecc2..181e6ed2e2 100644 --- a/libraries/SITL/SIM_Gimbal.cpp +++ b/libraries/SITL/SIM_Gimbal.cpp @@ -24,6 +24,8 @@ extern const AP_HAL::HAL& hal; +namespace SITL { + Gimbal::Gimbal(const struct sitl_fdm &_fdm) : fdm(_fdm), target_address("127.0.0.1"), @@ -291,4 +293,7 @@ void Gimbal::send_report(void) delta_angle.zero(); } } + +} // namespace SITL + #endif // CONFIG_HAL_BOARD diff --git a/libraries/SITL/SIM_Gimbal.h b/libraries/SITL/SIM_Gimbal.h index 92bd43f1ce..9748c7ed52 100644 --- a/libraries/SITL/SIM_Gimbal.h +++ b/libraries/SITL/SIM_Gimbal.h @@ -24,6 +24,8 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include +namespace SITL { + class Gimbal { public: @@ -105,6 +107,9 @@ private: void send_report(void); }; + +} // namespace SITL + #endif // CONFIG_HAL_BOARD #endif // _SIM_GIMBAL_H diff --git a/libraries/SITL/SIM_Helicopter.cpp b/libraries/SITL/SIM_Helicopter.cpp index 36c24dfd92..e8329c54a5 100644 --- a/libraries/SITL/SIM_Helicopter.cpp +++ b/libraries/SITL/SIM_Helicopter.cpp @@ -22,6 +22,8 @@ #include "SIM_Helicopter.h" #include +namespace SITL { + /* constructor */ @@ -209,4 +211,7 @@ void Helicopter::update(const struct sitl_input &input) // update lat/lon/altitude update_position(); } + +} // namespace SITL + #endif // CONFIG_HAL_BOARD diff --git a/libraries/SITL/SIM_Helicopter.h b/libraries/SITL/SIM_Helicopter.h index 0a573aa7ad..e02f3e4988 100644 --- a/libraries/SITL/SIM_Helicopter.h +++ b/libraries/SITL/SIM_Helicopter.h @@ -22,6 +22,8 @@ #include "SIM_Aircraft.h" +namespace SITL { + /* a helicopter simulator */ @@ -59,5 +61,6 @@ private: bool gas_heli = false; }; +} // namespace SITL #endif // _SIM_HELICOPTER_H diff --git a/libraries/SITL/SIM_JSBSim.cpp b/libraries/SITL/SIM_JSBSim.cpp index b4856c455e..d4d4a48c84 100644 --- a/libraries/SITL/SIM_JSBSim.cpp +++ b/libraries/SITL/SIM_JSBSim.cpp @@ -30,6 +30,8 @@ extern const AP_HAL::HAL& hal; +namespace SITL { + // the asprintf() calls are not worth checking for SITL #pragma GCC diagnostic ignored "-Wunused-result" @@ -456,4 +458,7 @@ void JSBSim::update(const struct sitl_input &input) sync_frame_time(); drain_control_socket(); } + +} // namespace SITL + #endif // CONFIG_HAL_BOARD diff --git a/libraries/SITL/SIM_JSBSim.h b/libraries/SITL/SIM_JSBSim.h index 894fd18f60..125133084e 100644 --- a/libraries/SITL/SIM_JSBSim.h +++ b/libraries/SITL/SIM_JSBSim.h @@ -23,6 +23,8 @@ #include "SIM_Aircraft.h" #include +namespace SITL { + /* a Jsbsim simulator */ @@ -175,4 +177,6 @@ public: void ByteSwap(void); }; +} // namespace SITL + #endif // _SIM_JSBSIM_H diff --git a/libraries/SITL/SIM_Multicopter.cpp b/libraries/SITL/SIM_Multicopter.cpp index 4c8f7fa863..b88c549624 100644 --- a/libraries/SITL/SIM_Multicopter.cpp +++ b/libraries/SITL/SIM_Multicopter.cpp @@ -22,6 +22,8 @@ #include "SIM_Multicopter.h" #include +namespace SITL { + Motor m(90, false, 1); static const Motor quad_plus_motors[4] = @@ -226,4 +228,7 @@ void MultiCopter::update(const struct sitl_input &input) // update lat/lon/altitude update_position(); } + +} // namespace SITL + #endif // CONFIG_HAL_BOARD diff --git a/libraries/SITL/SIM_Multicopter.h b/libraries/SITL/SIM_Multicopter.h index 8c85b39482..8d1db9adcb 100644 --- a/libraries/SITL/SIM_Multicopter.h +++ b/libraries/SITL/SIM_Multicopter.h @@ -22,6 +22,8 @@ #include "SIM_Aircraft.h" +namespace SITL { + /* class to describe a motor position */ @@ -80,5 +82,6 @@ private: float thrust_scale; }; +} // namespace SITL #endif // _SIM_MULTICOPTER_H diff --git a/libraries/SITL/SIM_Rover.cpp b/libraries/SITL/SIM_Rover.cpp index 2a3f42fd83..f6f46a81db 100644 --- a/libraries/SITL/SIM_Rover.cpp +++ b/libraries/SITL/SIM_Rover.cpp @@ -23,6 +23,8 @@ #include #include +namespace SITL { + /* constructor */ @@ -157,4 +159,7 @@ void SimRover::update(const struct sitl_input &input) // update lat/lon/altitude update_position(); } + +} // namespace SITL + #endif // CONFIG_HAL_BOARD diff --git a/libraries/SITL/SIM_Rover.h b/libraries/SITL/SIM_Rover.h index 6dd6e1ed36..a823d78b26 100644 --- a/libraries/SITL/SIM_Rover.h +++ b/libraries/SITL/SIM_Rover.h @@ -22,6 +22,8 @@ #include "SIM_Aircraft.h" +namespace SITL { + /* a rover simulator */ @@ -53,5 +55,6 @@ private: float calc_lat_accel(float steering_angle, float speed); }; +} // namespace SITL #endif // _SIM_ROVER_H diff --git a/libraries/SITL/SIM_Tracker.cpp b/libraries/SITL/SIM_Tracker.cpp index 956748d3c3..e8820c7f92 100644 --- a/libraries/SITL/SIM_Tracker.cpp +++ b/libraries/SITL/SIM_Tracker.cpp @@ -21,6 +21,8 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include +namespace SITL { + Tracker::Tracker(const char *home_str, const char *frame_str) : Aircraft(home_str, frame_str) {} @@ -135,4 +137,6 @@ void Tracker::update(const struct sitl_input &input) update_position(); } +} // namespace SITL + #endif diff --git a/libraries/SITL/SIM_Tracker.h b/libraries/SITL/SIM_Tracker.h index 81e4dff014..2ab298e7ca 100644 --- a/libraries/SITL/SIM_Tracker.h +++ b/libraries/SITL/SIM_Tracker.h @@ -22,6 +22,8 @@ #include "SIM_Aircraft.h" +namespace SITL { + /* a antenna tracker simulator */ @@ -57,4 +59,6 @@ private: void update_onoff_servos(float &yaw_rate, float &pitch_rate); }; +} // namespace SITL + #endif diff --git a/libraries/SITL/SIM_last_letter.cpp b/libraries/SITL/SIM_last_letter.cpp index 9a0f26e4bd..a9c5bd2773 100644 --- a/libraries/SITL/SIM_last_letter.cpp +++ b/libraries/SITL/SIM_last_letter.cpp @@ -27,6 +27,8 @@ extern const AP_HAL::HAL& hal; +namespace SITL { + /* constructor */ @@ -143,4 +145,7 @@ void last_letter::update(const struct sitl_input &input) recv_fdm(input); sync_frame_time(); } + +} // namespace SITL + #endif // CONFIG_HAL_BOARD diff --git a/libraries/SITL/SIM_last_letter.h b/libraries/SITL/SIM_last_letter.h index cbae765efe..0d4b944fbf 100644 --- a/libraries/SITL/SIM_last_letter.h +++ b/libraries/SITL/SIM_last_letter.h @@ -23,6 +23,8 @@ #include "SIM_Aircraft.h" #include +namespace SITL { + /* a last_letter simulator */ @@ -74,5 +76,6 @@ private: const char *frame_str; }; +} // namespace SITL #endif // _SIM_LAST_LETTER_H diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index 92aa605861..1d5be1bbf6 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -25,6 +25,8 @@ extern const AP_HAL::HAL& hal; +namespace SITL { + // table of user settable parameters const AP_Param::GroupInfo SITL::var_info[] PROGMEM = { AP_GROUPINFO("BARO_RND", 0, SITL, baro_noise, 0.2f), @@ -170,3 +172,4 @@ Vector3f SITL::convert_earth_frame(const Matrix3f &dcm, const Vector3f &gyro) return Vector3f(phiDot, thetaDot, psiDot); } +} // namespace SITL diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index bed0d0ab74..5b4bcc9009 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -9,6 +9,8 @@ #include #include +namespace SITL { + struct PACKED sitl_fdm { // this is the packet sent by the simulator // to the APM executable to update the simulator state @@ -119,4 +121,6 @@ public: static Vector3f convert_earth_frame(const Matrix3f &dcm, const Vector3f &gyro); }; +} // namespace SITL + #endif // __SITL_H__