mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 18:34:19 -04:00
AP_Limits: Configuration defaults moved to config.h. Fixed AP_LIMITS==DISABLED handling.
This commit is contained in:
parent
9e4d118fdb
commit
a976a59c88
@ -109,20 +109,3 @@
|
|||||||
// #define MOT_6 CH_4
|
// #define MOT_6 CH_4
|
||||||
// #define MOT_7 CH_7
|
// #define MOT_7 CH_7
|
||||||
// #define MOT_8 CH_8
|
// #define MOT_8 CH_8
|
||||||
|
|
||||||
|
|
||||||
///
|
|
||||||
//
|
|
||||||
// AP_Limits
|
|
||||||
//
|
|
||||||
//
|
|
||||||
|
|
||||||
|
|
||||||
// Enable/disable AP_Limits
|
|
||||||
#define AP_LIMITS ENABLED
|
|
||||||
|
|
||||||
// Use PIN for displaying LIMITS status. 0 is disabled.
|
|
||||||
#define LIMITS_TRIGGERED_PIN 0
|
|
||||||
|
|
||||||
// PWM of "on" state for LIM_CHANNEL
|
|
||||||
#define LIMITS_ENABLE_PWM 1800
|
|
||||||
|
@ -1291,7 +1291,7 @@ static void fifty_hz_loop()
|
|||||||
static void slow_loop()
|
static void slow_loop()
|
||||||
{
|
{
|
||||||
|
|
||||||
#ifdef AP_LIMITS
|
#if AP_LIMITS == ENABLED
|
||||||
|
|
||||||
// Run the AP_Limits main loop
|
// Run the AP_Limits main loop
|
||||||
limits_loop();
|
limits_loop();
|
||||||
|
@ -93,7 +93,7 @@ static NOINLINE void send_attitude(mavlink_channel_t chan)
|
|||||||
omega.z);
|
omega.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef AP_LIMITS
|
#if AP_LIMITS == ENABLED
|
||||||
static NOINLINE void send_limits_status(mavlink_channel_t chan)
|
static NOINLINE void send_limits_status(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
limits_send_mavlink_status(chan);
|
limits_send_mavlink_status(chan);
|
||||||
@ -585,7 +585,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
|
|||||||
send_statustext(chan);
|
send_statustext(chan);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef AP_LIMITS
|
#if AP_LIMITS == ENABLED
|
||||||
|
|
||||||
case MSG_LIMITS_STATUS:
|
case MSG_LIMITS_STATUS:
|
||||||
CHECK_PAYLOAD_SIZE(LIMITS_STATUS);
|
CHECK_PAYLOAD_SIZE(LIMITS_STATUS);
|
||||||
|
@ -962,6 +962,44 @@
|
|||||||
# define ALLOW_RC_OVERRIDE DISABLED
|
# define ALLOW_RC_OVERRIDE DISABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
// AP_Limits Defaults
|
||||||
|
//
|
||||||
|
|
||||||
|
|
||||||
|
// Enable/disable AP_Limits
|
||||||
|
#ifndef AP_LIMITS
|
||||||
|
#define AP_LIMITS ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Use PIN for displaying LIMITS status. 0 is disabled.
|
||||||
|
#ifndef LIMITS_TRIGGERED_PIN
|
||||||
|
#define LIMITS_TRIGGERED_PIN 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// PWM of "on" state for LIM_CHANNEL
|
||||||
|
#ifndef LIMITS_ENABLE_PWM
|
||||||
|
#define LIMITS_ENABLE_PWM 1800
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef LIM_ENABLED
|
||||||
|
#define LIM_ENABLED 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef LIM_ALT_ON
|
||||||
|
#define LIM_ALT_ON 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef LIM_FNC_ON
|
||||||
|
#define LIM_FNC_ON 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef LIM_GPSLCK_ON
|
||||||
|
#define LIM_GPSLCK_ON 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Developer Items
|
// Developer Items
|
||||||
//
|
//
|
||||||
|
Loading…
Reference in New Issue
Block a user