mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
SITL: enable the SIM_* parameters in ArduCopter and ArduPlane
This commit is contained in:
parent
117bae9585
commit
1cb96e14a9
@ -186,6 +186,8 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
|
|||||||
#ifdef DESKTOP_BUILD
|
#ifdef DESKTOP_BUILD
|
||||||
AP_Baro_BMP085_HIL barometer;
|
AP_Baro_BMP085_HIL barometer;
|
||||||
AP_Compass_HIL compass;
|
AP_Compass_HIL compass;
|
||||||
|
#include <SITL.h>
|
||||||
|
SITL sitl;
|
||||||
#else
|
#else
|
||||||
|
|
||||||
#if CONFIG_BARO == AP_BARO_BMP085
|
#if CONFIG_BARO == AP_BARO_BMP085
|
||||||
|
@ -280,26 +280,10 @@ static void NOINLINE send_ahrs(mavlink_channel_t chan)
|
|||||||
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
|
|
||||||
#ifdef DESKTOP_BUILD
|
#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
|
// report simulator state
|
||||||
static void NOINLINE send_simstate(mavlink_channel_t chan)
|
static void NOINLINE send_simstate(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
extern void sitl_simstate_send(uint8_t chan);
|
sitl.simstate_send(chan);
|
||||||
sitl_simstate_send((uint8_t)chan);
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -51,13 +51,14 @@ public:
|
|||||||
k_param_format_version = 0,
|
k_param_format_version = 0,
|
||||||
k_param_software_type,
|
k_param_software_type,
|
||||||
|
|
||||||
|
// simulation
|
||||||
|
k_param_sitl = 10,
|
||||||
|
|
||||||
// Misc
|
// Misc
|
||||||
//
|
//
|
||||||
k_param_log_bitmask = 20,
|
k_param_log_bitmask = 20,
|
||||||
k_param_log_last_filenumber, // *** Deprecated - remove with next eeprom number change
|
k_param_log_last_filenumber, // *** Deprecated - remove with next eeprom number change
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
|
||||||
//
|
//
|
||||||
// 80: Heli
|
// 80: Heli
|
||||||
//
|
//
|
||||||
@ -65,7 +66,6 @@ public:
|
|||||||
k_param_heli_servo_2,
|
k_param_heli_servo_2,
|
||||||
k_param_heli_servo_3,
|
k_param_heli_servo_3,
|
||||||
k_param_heli_servo_4,
|
k_param_heli_servo_4,
|
||||||
#endif
|
|
||||||
|
|
||||||
//
|
//
|
||||||
// 90: Motors
|
// 90: Motors
|
||||||
|
@ -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
|
// @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
|
||||||
|
GOBJECT(sitl, "SIM_", SITL),
|
||||||
|
#endif
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
// @Group: H_
|
// @Group: H_
|
||||||
// @Path: ../libraries/AP_Motors/AP_MotorsHeli.cpp
|
// @Path: ../libraries/AP_Motors/AP_MotorsHeli.cpp
|
||||||
|
@ -150,6 +150,8 @@ static AP_ADC_ADS7844 adc;
|
|||||||
#ifdef DESKTOP_BUILD
|
#ifdef DESKTOP_BUILD
|
||||||
AP_Baro_BMP085_HIL barometer;
|
AP_Baro_BMP085_HIL barometer;
|
||||||
AP_Compass_HIL compass;
|
AP_Compass_HIL compass;
|
||||||
|
#include <SITL.h>
|
||||||
|
SITL sitl;
|
||||||
#else
|
#else
|
||||||
|
|
||||||
#if CONFIG_BARO == AP_BARO_BMP085
|
#if CONFIG_BARO == AP_BARO_BMP085
|
||||||
|
@ -501,26 +501,10 @@ static void NOINLINE send_ahrs(mavlink_channel_t chan)
|
|||||||
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
|
|
||||||
#ifdef DESKTOP_BUILD
|
#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
|
// report simulator state
|
||||||
static void NOINLINE send_simstate(mavlink_channel_t chan)
|
static void NOINLINE send_simstate(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
extern void sitl_simstate_send(uint8_t chan);
|
sitl.simstate_send(chan);
|
||||||
sitl_simstate_send((uint8_t)chan);
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -70,7 +70,6 @@ public:
|
|||||||
k_param_reset_switch_chan,
|
k_param_reset_switch_chan,
|
||||||
k_param_manual_level,
|
k_param_manual_level,
|
||||||
|
|
||||||
|
|
||||||
// 110: Telemetry control
|
// 110: Telemetry control
|
||||||
//
|
//
|
||||||
k_param_gcs0 = 110, // stream rates for port0
|
k_param_gcs0 = 110, // stream rates for port0
|
||||||
@ -185,6 +184,9 @@ public:
|
|||||||
k_param_fence_minalt,
|
k_param_fence_minalt,
|
||||||
k_param_fence_maxalt,
|
k_param_fence_maxalt,
|
||||||
|
|
||||||
|
// simulator control
|
||||||
|
k_param_sitl = 230,
|
||||||
|
|
||||||
//
|
//
|
||||||
// 240: PID Controllers
|
// 240: PID Controllers
|
||||||
//
|
//
|
||||||
|
@ -326,7 +326,12 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
|
|
||||||
// @Group: AHRS_
|
// @Group: AHRS_
|
||||||
// @Path: ../libraries/AP_AHRS/AP_AHRS_DCM.cpp, ../libraries/AP_AHRS/AP_AHRS_Quaternion.cpp
|
// @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…
Reference in New Issue
Block a user