Tools: use new AP_PERIPH_RC_OUT_ENABLED define

This commit is contained in:
Shiv Tyagi 2025-02-20 22:19:15 +05:30 committed by Peter Barker
parent 1793c4c5f1
commit 6a429b887a
7 changed files with 27 additions and 25 deletions

View File

@ -185,7 +185,7 @@ void AP_Periph_FW::init()
rcin_init();
#endif
#if defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_RC_OUT)
#if defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) || AP_PERIPH_RC_OUT_ENABLED
hal.rcout->init();
#endif
@ -193,7 +193,7 @@ void AP_Periph_FW::init()
hal.rcout->set_serial_led_num_LEDs(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY, AP_HAL::RCOutput::MODE_NEOPIXEL);
#endif
#ifdef HAL_PERIPH_ENABLE_RC_OUT
#if AP_PERIPH_RC_OUT_ENABLED
rcout_init();
#endif
@ -452,7 +452,7 @@ void AP_Periph_FW::update()
check_for_serial_reboot_cmd(HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT);
#endif
#ifdef HAL_PERIPH_ENABLE_RC_OUT
#if AP_PERIPH_RC_OUT_ENABLED
rcout_init_1Hz();
#endif
@ -604,7 +604,7 @@ void AP_Periph_FW::check_for_serial_reboot_cmd(const int8_t serial_index)
// This is copied from AP_Vehicle::reboot(bool hold_in_bootloader) minus the actual reboot
void AP_Periph_FW::prepare_reboot()
{
#ifdef HAL_PERIPH_ENABLE_RC_OUT
#if AP_PERIPH_RC_OUT_ENABLED
// force safety on
hal.rcout->force_safety_on();
#endif

View File

@ -78,8 +78,8 @@
#endif
#if AP_PERIPH_NOTIFY_ENABLED
#if !defined(HAL_PERIPH_ENABLE_RC_OUT) && !defined(HAL_PERIPH_NOTIFY_WITHOUT_RCOUT)
#error "AP_PERIPH_NOTIFY_ENABLED requires HAL_PERIPH_ENABLE_RC_OUT"
#if !AP_PERIPH_RC_OUT_ENABLED && !defined(HAL_PERIPH_NOTIFY_WITHOUT_RCOUT)
#error "AP_PERIPH_NOTIFY_ENABLED requires AP_PERIPH_RC_OUT_ENABLED"
#endif
#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY
#error "You cannot enable AP_PERIPH_NOTIFY_ENABLED and HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY at the same time. Notify already includes it"
@ -97,7 +97,7 @@
#endif
#ifndef AP_PERIPH_SAFETY_SWITCH_ENABLED
#define AP_PERIPH_SAFETY_SWITCH_ENABLED defined(HAL_PERIPH_ENABLE_RC_OUT)
#define AP_PERIPH_SAFETY_SWITCH_ENABLED AP_PERIPH_RC_OUT_ENABLED
#endif
#ifndef HAL_PERIPH_CAN_MIRROR
@ -340,7 +340,7 @@ public:
void apd_esc_telem_update();
#endif
#ifdef HAL_PERIPH_ENABLE_RC_OUT
#if AP_PERIPH_RC_OUT_ENABLED
#if HAL_WITH_ESC_TELEM
AP_ESC_Telem esc_telem;
uint8_t get_motor_number(const uint8_t esc_number) const;

View File

@ -401,7 +401,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GARRAY(esc_number, 0, "ESC_NUMBER", 0),
#endif
#ifdef HAL_PERIPH_ENABLE_RC_OUT
#if AP_PERIPH_RC_OUT_ENABLED
// Servo driver
// @Group: OUT
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp

View File

@ -177,7 +177,7 @@ public:
AP_Int8 msp_port;
#endif
#ifdef HAL_PERIPH_ENABLE_RC_OUT
#if AP_PERIPH_RC_OUT_ENABLED
AP_Int16 esc_rate;
AP_Int8 esc_pwm_type;
AP_Int16 esc_command_timeout_ms;

View File

@ -492,7 +492,7 @@ void AP_Periph_FW::handle_allocation_response(CanardInstance* canard_instance, C
}
#if defined(HAL_GPIO_PIN_SAFE_LED) || defined(HAL_PERIPH_ENABLE_RC_OUT)
#if defined(HAL_GPIO_PIN_SAFE_LED) || AP_PERIPH_RC_OUT_ENABLED
static uint8_t safety_state;
/*
@ -530,9 +530,9 @@ void AP_Periph_FW::set_rgb_led(uint8_t red, uint8_t green, uint8_t blue)
{
#if AP_PERIPH_NOTIFY_ENABLED
notify.handle_rgb(red, green, blue);
#ifdef HAL_PERIPH_ENABLE_RC_OUT
#if AP_PERIPH_RC_OUT_ENABLED
rcout_has_new_data_to_update = true;
#endif // HAL_PERIPH_ENABLE_RC_OUT
#endif // AP_PERIPH_RC_OUT_ENABLED
#endif // AP_PERIPH_NOTIFY_ENABLED
#ifdef HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY
@ -639,7 +639,7 @@ void AP_Periph_FW::handle_lightscommand(CanardInstance* canard_instance, CanardR
}
#endif // AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
#ifdef HAL_PERIPH_ENABLE_RC_OUT
#if AP_PERIPH_RC_OUT_ENABLED
void AP_Periph_FW::handle_esc_rawcommand(CanardInstance* canard_instance, CanardRxTransfer* transfer)
{
uavcan_equipment_esc_RawCommand cmd;
@ -672,7 +672,7 @@ void AP_Periph_FW::handle_act_command(CanardInstance* canard_instance, CanardRxT
}
}
}
#endif // HAL_PERIPH_ENABLE_RC_OUT
#endif // AP_PERIPH_RC_OUT_ENABLED
#if AP_PERIPH_NOTIFY_ENABLED
void AP_Periph_FW::handle_notify_state(CanardInstance* canard_instance, CanardRxTransfer* transfer)
@ -830,7 +830,7 @@ void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance,
break;
#endif
#if defined(HAL_GPIO_PIN_SAFE_LED) || defined(HAL_PERIPH_ENABLE_RC_OUT)
#if defined(HAL_GPIO_PIN_SAFE_LED) || AP_PERIPH_RC_OUT_ENABLED
case ARDUPILOT_INDICATION_SAFETYSTATE_ID:
handle_safety_state(canard_instance, transfer);
break;
@ -864,7 +864,7 @@ void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance,
break;
#endif
#ifdef HAL_PERIPH_ENABLE_RC_OUT
#if AP_PERIPH_RC_OUT_ENABLED
case UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID:
handle_esc_rawcommand(canard_instance, transfer);
break;
@ -950,7 +950,7 @@ bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance,
*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_SIGNATURE;
return true;
#endif
#if defined(HAL_GPIO_PIN_SAFE_LED) || defined(HAL_PERIPH_ENABLE_RC_OUT)
#if defined(HAL_GPIO_PIN_SAFE_LED) || AP_PERIPH_RC_OUT_ENABLED
case ARDUPILOT_INDICATION_SAFETYSTATE_ID:
*out_data_type_signature = ARDUPILOT_INDICATION_SAFETYSTATE_SIGNATURE;
return true;
@ -981,7 +981,7 @@ bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance,
return true;
#endif
#ifdef HAL_PERIPH_ENABLE_RC_OUT
#if AP_PERIPH_RC_OUT_ENABLED
case UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID:
*out_data_type_signature = UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_SIGNATURE;
return true;
@ -1704,7 +1704,7 @@ void AP_Periph_FW::can_start()
}
#ifdef HAL_PERIPH_ENABLE_RC_OUT
#if AP_PERIPH_RC_OUT_ENABLED
#if HAL_WITH_ESC_TELEM
// try to map the ESC number to a motor number. This is needed
// for when we have multiple CAN nodes, one for each ESC
@ -1873,7 +1873,7 @@ void AP_Periph_FW::apd_esc_telem_update()
}
#endif // HAL_PERIPH_ENABLE_ESC_APD
#endif // HAL_PERIPH_ENABLE_RC_OUT
#endif // AP_PERIPH_RC_OUT_ENABLED
void AP_Periph_FW::can_update()
{
@ -1957,7 +1957,7 @@ void AP_Periph_FW::can_update()
#ifdef HAL_PERIPH_ENABLE_MSP
msp_sensor_update();
#endif
#ifdef HAL_PERIPH_ENABLE_RC_OUT
#if AP_PERIPH_RC_OUT_ENABLED
rcout_update();
#endif
#if AP_PERIPH_EFI_ENABLED

View File

@ -13,7 +13,7 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#ifdef HAL_PERIPH_ENABLE_RC_OUT
#if AP_PERIPH_RC_OUT_ENABLED
#include "AP_Periph.h"
#if AP_SIM_ENABLED
#include <dronecan_msgs.h>
@ -225,4 +225,4 @@ void AP_Periph_FW::sim_update_actuator(uint8_t actuator_id)
}
#endif // AP_SIM_ENABLED
#endif // HAL_PERIPH_ENABLE_RC_OUT
#endif // AP_PERIPH_RC_OUT_ENABLED

View File

@ -964,7 +964,7 @@ class sitl_periph_universal(sitl_periph):
AP_PERIPH_RPM_ENABLED = 1,
AP_PERIPH_RPM_STREAM_ENABLED = 1,
AP_RPM_STREAM_ENABLED = 1,
HAL_PERIPH_ENABLE_RC_OUT = 1,
AP_PERIPH_RC_OUT_ENABLED = 1,
AP_PERIPH_ADSB_ENABLED = 1,
HAL_PERIPH_ENABLE_SERIAL_OPTIONS = 1,
AP_AIRSPEED_ENABLED = 1,
@ -1000,6 +1000,7 @@ class sitl_periph_gps(sitl_periph):
AP_PERIPH_BARO_ENABLED = 0,
AP_PERIPH_EFI_ENABLED = 0,
AP_PERIPH_RANGEFINDER_ENABLED = 0,
AP_PERIPH_RC_OUT_ENABLED = 0,
AP_PERIPH_RTC_ENABLED = 0,
AP_PERIPH_RCIN_ENABLED = 0,
AP_PERIPH_RPM_ENABLED = 0,
@ -1030,6 +1031,7 @@ class sitl_periph_battmon(sitl_periph):
AP_PERIPH_MAG_ENABLED = 0,
AP_PERIPH_EFI_ENABLED = 0,
AP_PERIPH_RTC_ENABLED = 0,
AP_PERIPH_RC_OUT_ENABLED = 0,
AP_PERIPH_RCIN_ENABLED = 0,
AP_PERIPH_RPM_ENABLED = 0,
AP_PERIPH_RPM_STREAM_ENABLED = 0,