Browse Source

SITL: enable the SIM_* parameters in ArduCopter and ArduPlane

master
Andrew Tridgell 13 years ago
parent
commit
55092c25a6
  1. 2
      ArduCopter/ArduCopter.pde
  2. 18
      ArduCopter/GCS_Mavlink.pde
  3. 4
      ArduCopter/Parameters.h
  4. 4
      ArduCopter/Parameters.pde
  5. 2
      ArduPlane/ArduPlane.pde
  6. 18
      ArduPlane/GCS_Mavlink.pde
  7. 4
      ArduPlane/Parameters.h
  8. 7
      ArduPlane/Parameters.pde

2
ArduCopter/ArduCopter.pde

@ -186,6 +186,8 @@ static AP_Int8 *flight_modes = &g.flight_mode1; @@ -186,6 +186,8 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
#ifdef DESKTOP_BUILD
AP_Baro_BMP085_HIL barometer;
AP_Compass_HIL compass;
#include <SITL.h>
SITL sitl;
#else
#if CONFIG_BARO == AP_BARO_BMP085

18
ArduCopter/GCS_Mavlink.pde

@ -280,26 +280,10 @@ static void NOINLINE send_ahrs(mavlink_channel_t chan) @@ -280,26 +280,10 @@ static void NOINLINE send_ahrs(mavlink_channel_t chan)
#endif // HIL_MODE != HIL_MODE_ATTITUDE
#ifdef DESKTOP_BUILD
void mavlink_simstate_send(uint8_t chan,
float roll,
float pitch,
float yaw,
float xAcc,
float yAcc,
float zAcc,
float p,
float q,
float r)
{
mavlink_msg_simstate_send((mavlink_channel_t)chan,
roll, pitch, yaw, xAcc, yAcc, zAcc, p, q, r);
}
// report simulator state
static void NOINLINE send_simstate(mavlink_channel_t chan)
{
extern void sitl_simstate_send(uint8_t chan);
sitl_simstate_send((uint8_t)chan);
sitl.simstate_send(chan);
}
#endif

4
ArduCopter/Parameters.h

@ -51,13 +51,14 @@ public: @@ -51,13 +51,14 @@ public:
k_param_format_version = 0,
k_param_software_type,
// simulation
k_param_sitl = 10,
// Misc
//
k_param_log_bitmask = 20,
k_param_log_last_filenumber, // *** Deprecated - remove with next eeprom number change
#if FRAME_CONFIG == HELI_FRAME
//
// 80: Heli
//
@ -65,7 +66,6 @@ public: @@ -65,7 +66,6 @@ public:
k_param_heli_servo_2,
k_param_heli_servo_3,
k_param_heli_servo_4,
#endif
//
// 90: Motors

4
ArduCopter/Parameters.pde

@ -227,6 +227,10 @@ static const AP_Param::Info var_info[] PROGMEM = { @@ -227,6 +227,10 @@ static const AP_Param::Info var_info[] PROGMEM = {
// @Path: ../libraries/AP_AHRS/AP_AHRS_DCM.cpp, ../libraries/AP_AHRS/AP_AHRS_Quaternion.cpp
GOBJECT(ahrs, "AHRS_", AP_AHRS),
#ifdef DESKTOP_BUILD
GOBJECT(sitl, "SIM_", SITL),
#endif
#if FRAME_CONFIG == HELI_FRAME
// @Group: H_
// @Path: ../libraries/AP_Motors/AP_MotorsHeli.cpp

2
ArduPlane/ArduPlane.pde

@ -150,6 +150,8 @@ static AP_ADC_ADS7844 adc; @@ -150,6 +150,8 @@ static AP_ADC_ADS7844 adc;
#ifdef DESKTOP_BUILD
AP_Baro_BMP085_HIL barometer;
AP_Compass_HIL compass;
#include <SITL.h>
SITL sitl;
#else
#if CONFIG_BARO == AP_BARO_BMP085

18
ArduPlane/GCS_Mavlink.pde

@ -501,26 +501,10 @@ static void NOINLINE send_ahrs(mavlink_channel_t chan) @@ -501,26 +501,10 @@ static void NOINLINE send_ahrs(mavlink_channel_t chan)
#endif // HIL_MODE != HIL_MODE_ATTITUDE
#ifdef DESKTOP_BUILD
void mavlink_simstate_send(uint8_t chan,
float roll,
float pitch,
float yaw,
float xAcc,
float yAcc,
float zAcc,
float p,
float q,
float r)
{
mavlink_msg_simstate_send((mavlink_channel_t)chan,
roll, pitch, yaw, xAcc, yAcc, zAcc, p, q, r);
}
// report simulator state
static void NOINLINE send_simstate(mavlink_channel_t chan)
{
extern void sitl_simstate_send(uint8_t chan);
sitl_simstate_send((uint8_t)chan);
sitl.simstate_send(chan);
}
#endif

4
ArduPlane/Parameters.h

@ -70,7 +70,6 @@ public: @@ -70,7 +70,6 @@ public:
k_param_reset_switch_chan,
k_param_manual_level,
// 110: Telemetry control
//
k_param_gcs0 = 110, // stream rates for port0
@ -185,6 +184,9 @@ public: @@ -185,6 +184,9 @@ public:
k_param_fence_minalt,
k_param_fence_maxalt,
// simulator control
k_param_sitl = 230,
//
// 240: PID Controllers
//

7
ArduPlane/Parameters.pde

@ -326,7 +326,12 @@ static const AP_Param::Info var_info[] PROGMEM = { @@ -326,7 +326,12 @@ static const AP_Param::Info var_info[] PROGMEM = {
// @Group: AHRS_
// @Path: ../libraries/AP_AHRS/AP_AHRS_DCM.cpp, ../libraries/AP_AHRS/AP_AHRS_Quaternion.cpp
GOBJECT(ahrs, "AHRS_", AP_AHRS)
GOBJECT(ahrs, "AHRS_", AP_AHRS),
#ifdef DESKTOP_BUILD
// @Group: SITL
GOBJECT(sitl, "SIM_", SITL),
#endif
};

Loading…
Cancel
Save