mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 18:53:57 -04:00
Tools: use new AP_PERIPH_NOTIFY_ENABLED define
This commit is contained in:
parent
44d07c8f79
commit
2b6bbedce6
@ -300,7 +300,7 @@ void AP_Periph_FW::init()
|
|||||||
rpm_sensor.init();
|
rpm_sensor.init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
#if AP_PERIPH_NOTIFY_ENABLED
|
||||||
notify.init();
|
notify.init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -314,13 +314,13 @@ void AP_Periph_FW::init()
|
|||||||
start_ms = AP_HAL::millis();
|
start_ms = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY)
|
#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || AP_PERIPH_NOTIFY_ENABLED
|
||||||
/*
|
/*
|
||||||
rotating rainbow pattern on startup
|
rotating rainbow pattern on startup
|
||||||
*/
|
*/
|
||||||
void AP_Periph_FW::update_rainbow()
|
void AP_Periph_FW::update_rainbow()
|
||||||
{
|
{
|
||||||
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
#if AP_PERIPH_NOTIFY_ENABLED
|
||||||
if (notify.get_led_len() != 8) {
|
if (notify.get_led_len() != 8) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -332,7 +332,7 @@ void AP_Periph_FW::update_rainbow()
|
|||||||
uint32_t now = AP_HAL::millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
if (now - start_ms > 1500) {
|
if (now - start_ms > 1500) {
|
||||||
rainbow_done = true;
|
rainbow_done = true;
|
||||||
#if defined (HAL_PERIPH_ENABLE_NOTIFY)
|
#if AP_PERIPH_NOTIFY_ENABLED
|
||||||
periph.notify.handle_rgb(0, 0, 0);
|
periph.notify.handle_rgb(0, 0, 0);
|
||||||
#elif defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)
|
#elif defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)
|
||||||
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, -1, 0, 0, 0);
|
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, -1, 0, 0, 0);
|
||||||
@ -365,7 +365,7 @@ void AP_Periph_FW::update_rainbow()
|
|||||||
float brightness = 0.3;
|
float brightness = 0.3;
|
||||||
for (uint8_t n=0; n<8; n++) {
|
for (uint8_t n=0; n<8; n++) {
|
||||||
uint8_t i = (step + n) % nsteps;
|
uint8_t i = (step + n) % nsteps;
|
||||||
#if defined (HAL_PERIPH_ENABLE_NOTIFY)
|
#if AP_PERIPH_NOTIFY_ENABLED
|
||||||
periph.notify.handle_rgb(
|
periph.notify.handle_rgb(
|
||||||
#elif defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)
|
#elif defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)
|
||||||
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, n,
|
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, n,
|
||||||
@ -380,7 +380,7 @@ void AP_Periph_FW::update_rainbow()
|
|||||||
hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);
|
hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
#endif // HAL_PERIPH_ENABLE_NOTIFY
|
#endif // AP_PERIPH_NOTIFY_ENABLED
|
||||||
|
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && CH_DBG_ENABLE_STACK_CHECK == TRUE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && CH_DBG_ENABLE_STACK_CHECK == TRUE
|
||||||
@ -505,7 +505,7 @@ void AP_Periph_FW::update()
|
|||||||
if (now - fiftyhz_last_update_ms >= 20) {
|
if (now - fiftyhz_last_update_ms >= 20) {
|
||||||
// update at 50Hz
|
// update at 50Hz
|
||||||
fiftyhz_last_update_ms = now;
|
fiftyhz_last_update_ms = now;
|
||||||
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
#if AP_PERIPH_NOTIFY_ENABLED
|
||||||
notify.update();
|
notify.update();
|
||||||
#endif
|
#endif
|
||||||
#if HAL_GCS_ENABLED
|
#if HAL_GCS_ENABLED
|
||||||
@ -539,7 +539,7 @@ void AP_Periph_FW::update()
|
|||||||
networking_periph.update();
|
networking_periph.update();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY)
|
#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || AP_PERIPH_NOTIFY_ENABLED
|
||||||
update_rainbow();
|
update_rainbow();
|
||||||
#endif
|
#endif
|
||||||
#if AP_PERIPH_ADSB_ENABLED
|
#if AP_PERIPH_ADSB_ENABLED
|
||||||
|
@ -77,18 +77,18 @@
|
|||||||
#define AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
|
#define AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
#if AP_PERIPH_NOTIFY_ENABLED
|
||||||
#if !defined(HAL_PERIPH_ENABLE_RC_OUT) && !defined(HAL_PERIPH_NOTIFY_WITHOUT_RCOUT)
|
#if !defined(HAL_PERIPH_ENABLE_RC_OUT) && !defined(HAL_PERIPH_NOTIFY_WITHOUT_RCOUT)
|
||||||
#error "HAL_PERIPH_ENABLE_NOTIFY requires HAL_PERIPH_ENABLE_RC_OUT"
|
#error "AP_PERIPH_NOTIFY_ENABLED requires HAL_PERIPH_ENABLE_RC_OUT"
|
||||||
#endif
|
#endif
|
||||||
#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY
|
#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY
|
||||||
#error "You cannot enable HAL_PERIPH_ENABLE_NOTIFY and HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY at the same time. Notify already includes it"
|
#error "You cannot enable AP_PERIPH_NOTIFY_ENABLED and HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY at the same time. Notify already includes it"
|
||||||
#endif
|
#endif
|
||||||
#ifdef AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
|
#ifdef AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
|
||||||
#error "You cannot enable HAL_PERIPH_ENABLE_NOTIFY and any HAL_PERIPH_ENABLE_<device>_LED_WITHOUT_NOTIFY at the same time. Notify already includes them all"
|
#error "You cannot enable AP_PERIPH_NOTIFY_ENABLED and any HAL_PERIPH_ENABLE_<device>_LED_WITHOUT_NOTIFY at the same time. Notify already includes them all"
|
||||||
#endif
|
#endif
|
||||||
#ifdef HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY
|
#ifdef HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY
|
||||||
#error "You cannot use HAL_PERIPH_ENABLE_NOTIFY and HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY at the same time. Notify already includes it. Set param OUTx_FUNCTION=120"
|
#error "You cannot use AP_PERIPH_NOTIFY_ENABLED and HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY at the same time. Notify already includes it. Set param OUTx_FUNCTION=120"
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -397,10 +397,10 @@ public:
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(HAL_PERIPH_ENABLE_NOTIFY) || defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY)
|
#if AP_PERIPH_NOTIFY_ENABLED || defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY)
|
||||||
void update_rainbow();
|
void update_rainbow();
|
||||||
#endif
|
#endif
|
||||||
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
#if AP_PERIPH_NOTIFY_ENABLED
|
||||||
// notification object for LEDs, buzzers etc
|
// notification object for LEDs, buzzers etc
|
||||||
AP_Notify notify;
|
AP_Notify notify;
|
||||||
uint64_t vehicle_state = 1; // default to initialisation
|
uint64_t vehicle_state = 1; // default to initialisation
|
||||||
|
@ -472,7 +472,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||||||
GSCALAR(msp_port, "MSP_PORT", AP_PERIPH_MSP_PORT_DEFAULT),
|
GSCALAR(msp_port, "MSP_PORT", AP_PERIPH_MSP_PORT_DEFAULT),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
#if AP_PERIPH_NOTIFY_ENABLED
|
||||||
// @Group: NTF_
|
// @Group: NTF_
|
||||||
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
|
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
|
||||||
GOBJECT(notify, "NTF_", AP_Notify),
|
GOBJECT(notify, "NTF_", AP_Notify),
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
#include "AP_Periph.h"
|
#include "AP_Periph.h"
|
||||||
|
|
||||||
#if defined(HAL_PERIPH_ENABLE_NOTIFY) || defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY)
|
#if AP_PERIPH_NOTIFY_ENABLED || defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY)
|
||||||
|
|
||||||
/*
|
/*
|
||||||
buzzer support
|
buzzer support
|
||||||
@ -33,7 +33,7 @@ void AP_Periph_FW::handle_beep_command(CanardInstance* canard_instance, CanardRx
|
|||||||
buzzer_len_ms = req.duration*1000;
|
buzzer_len_ms = req.duration*1000;
|
||||||
#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY
|
#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY
|
||||||
float volume = constrain_float(periph.g.buzz_volume*0.01f, 0, 1);
|
float volume = constrain_float(periph.g.buzz_volume*0.01f, 0, 1);
|
||||||
#elif defined(HAL_PERIPH_ENABLE_NOTIFY)
|
#elif AP_PERIPH_NOTIFY_ENABLED
|
||||||
float volume = constrain_float(periph.notify.get_buzz_volume()*0.01f, 0, 1);
|
float volume = constrain_float(periph.notify.get_buzz_volume()*0.01f, 0, 1);
|
||||||
#endif
|
#endif
|
||||||
hal.util->toneAlarm_set_buzzer_tone(req.frequency, volume, uint32_t(req.duration*1000));
|
hal.util->toneAlarm_set_buzzer_tone(req.frequency, volume, uint32_t(req.duration*1000));
|
||||||
@ -53,4 +53,4 @@ void AP_Periph_FW::can_buzzer_update(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // (HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || (HAL_PERIPH_ENABLE_NOTIFY)
|
#endif // (HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || AP_PERIPH_NOTIFY_ENABLED
|
||||||
|
@ -525,15 +525,15 @@ void AP_Periph_FW::handle_arming_status(CanardInstance* canard_instance, CanardR
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
#if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_NOTIFY)
|
#if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || AP_PERIPH_NOTIFY_ENABLED
|
||||||
void AP_Periph_FW::set_rgb_led(uint8_t red, uint8_t green, uint8_t blue)
|
void AP_Periph_FW::set_rgb_led(uint8_t red, uint8_t green, uint8_t blue)
|
||||||
{
|
{
|
||||||
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
#if AP_PERIPH_NOTIFY_ENABLED
|
||||||
notify.handle_rgb(red, green, blue);
|
notify.handle_rgb(red, green, blue);
|
||||||
#ifdef HAL_PERIPH_ENABLE_RC_OUT
|
#ifdef HAL_PERIPH_ENABLE_RC_OUT
|
||||||
rcout_has_new_data_to_update = true;
|
rcout_has_new_data_to_update = true;
|
||||||
#endif // HAL_PERIPH_ENABLE_RC_OUT
|
#endif // HAL_PERIPH_ENABLE_RC_OUT
|
||||||
#endif // HAL_PERIPH_ENABLE_NOTIFY
|
#endif // AP_PERIPH_NOTIFY_ENABLED
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY
|
#ifdef HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY
|
||||||
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, -1, red, green, blue);
|
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, -1, red, green, blue);
|
||||||
@ -623,7 +623,7 @@ void AP_Periph_FW::handle_lightscommand(CanardInstance* canard_instance, CanardR
|
|||||||
uint8_t red = cmd.color.red<<3U;
|
uint8_t red = cmd.color.red<<3U;
|
||||||
uint8_t green = (cmd.color.green>>1U)<<3U;
|
uint8_t green = (cmd.color.green>>1U)<<3U;
|
||||||
uint8_t blue = cmd.color.blue<<3U;
|
uint8_t blue = cmd.color.blue<<3U;
|
||||||
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
#if AP_PERIPH_NOTIFY_ENABLED
|
||||||
const int8_t brightness = notify.get_rgb_led_brightness_percent();
|
const int8_t brightness = notify.get_rgb_led_brightness_percent();
|
||||||
#elif defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY)
|
#elif defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY)
|
||||||
const int8_t brightness = g.led_brightness;
|
const int8_t brightness = g.led_brightness;
|
||||||
@ -674,7 +674,7 @@ void AP_Periph_FW::handle_act_command(CanardInstance* canard_instance, CanardRxT
|
|||||||
}
|
}
|
||||||
#endif // HAL_PERIPH_ENABLE_RC_OUT
|
#endif // HAL_PERIPH_ENABLE_RC_OUT
|
||||||
|
|
||||||
#if defined(HAL_PERIPH_ENABLE_NOTIFY)
|
#if AP_PERIPH_NOTIFY_ENABLED
|
||||||
void AP_Periph_FW::handle_notify_state(CanardInstance* canard_instance, CanardRxTransfer* transfer)
|
void AP_Periph_FW::handle_notify_state(CanardInstance* canard_instance, CanardRxTransfer* transfer)
|
||||||
{
|
{
|
||||||
ardupilot_indication_NotifyState msg;
|
ardupilot_indication_NotifyState msg;
|
||||||
@ -689,7 +689,7 @@ void AP_Periph_FW::handle_notify_state(CanardInstance* canard_instance, CanardRx
|
|||||||
vehicle_state = msg.vehicle_state;
|
vehicle_state = msg.vehicle_state;
|
||||||
last_vehicle_state = AP_HAL::millis();
|
last_vehicle_state = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
#endif // HAL_PERIPH_ENABLE_NOTIFY
|
#endif // AP_PERIPH_NOTIFY_ENABLED
|
||||||
|
|
||||||
#ifdef HAL_GPIO_PIN_SAFE_LED
|
#ifdef HAL_GPIO_PIN_SAFE_LED
|
||||||
/*
|
/*
|
||||||
@ -824,7 +824,7 @@ void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance,
|
|||||||
handle_param_executeopcode(canard_instance, transfer);
|
handle_param_executeopcode(canard_instance, transfer);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || defined (HAL_PERIPH_ENABLE_NOTIFY)
|
#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || AP_PERIPH_NOTIFY_ENABLED
|
||||||
case UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_ID:
|
case UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_ID:
|
||||||
handle_beep_command(canard_instance, transfer);
|
handle_beep_command(canard_instance, transfer);
|
||||||
break;
|
break;
|
||||||
@ -858,7 +858,7 @@ void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance,
|
|||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_NOTIFY)
|
#if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || AP_PERIPH_NOTIFY_ENABLED
|
||||||
case UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_ID:
|
case UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_ID:
|
||||||
handle_lightscommand(canard_instance, transfer);
|
handle_lightscommand(canard_instance, transfer);
|
||||||
break;
|
break;
|
||||||
@ -874,7 +874,7 @@ void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance,
|
|||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
#if AP_PERIPH_NOTIFY_ENABLED
|
||||||
case ARDUPILOT_INDICATION_NOTIFYSTATE_ID:
|
case ARDUPILOT_INDICATION_NOTIFYSTATE_ID:
|
||||||
handle_notify_state(canard_instance, transfer);
|
handle_notify_state(canard_instance, transfer);
|
||||||
break;
|
break;
|
||||||
@ -945,7 +945,7 @@ bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance,
|
|||||||
case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID:
|
case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID:
|
||||||
*out_data_type_signature = UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE;
|
*out_data_type_signature = UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE;
|
||||||
return true;
|
return true;
|
||||||
#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || defined (HAL_PERIPH_ENABLE_NOTIFY)
|
#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || AP_PERIPH_NOTIFY_ENABLED
|
||||||
case UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_ID:
|
case UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_ID:
|
||||||
*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_SIGNATURE;
|
*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_SIGNATURE;
|
||||||
return true;
|
return true;
|
||||||
@ -958,7 +958,7 @@ bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance,
|
|||||||
case UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID:
|
case UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID:
|
||||||
*out_data_type_signature = UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_SIGNATURE;
|
*out_data_type_signature = UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_SIGNATURE;
|
||||||
return true;
|
return true;
|
||||||
#if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_NOTIFY)
|
#if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || AP_PERIPH_NOTIFY_ENABLED
|
||||||
case UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_ID:
|
case UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_ID:
|
||||||
*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_SIGNATURE;
|
*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_SIGNATURE;
|
||||||
return true;
|
return true;
|
||||||
@ -990,7 +990,7 @@ bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance,
|
|||||||
*out_data_type_signature = UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_SIGNATURE;
|
*out_data_type_signature = UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_SIGNATURE;
|
||||||
return true;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
#if defined(HAL_PERIPH_ENABLE_NOTIFY)
|
#if AP_PERIPH_NOTIFY_ENABLED
|
||||||
case ARDUPILOT_INDICATION_NOTIFYSTATE_ID:
|
case ARDUPILOT_INDICATION_NOTIFYSTATE_ID:
|
||||||
*out_data_type_signature = ARDUPILOT_INDICATION_NOTIFYSTATE_SIGNATURE;
|
*out_data_type_signature = ARDUPILOT_INDICATION_NOTIFYSTATE_SIGNATURE;
|
||||||
return true;
|
return true;
|
||||||
@ -1936,7 +1936,7 @@ void AP_Periph_FW::can_update()
|
|||||||
#ifdef HAL_PERIPH_ENABLE_PROXIMITY
|
#ifdef HAL_PERIPH_ENABLE_PROXIMITY
|
||||||
can_proximity_update();
|
can_proximity_update();
|
||||||
#endif
|
#endif
|
||||||
#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || defined (HAL_PERIPH_ENABLE_NOTIFY)
|
#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || AP_PERIPH_NOTIFY_ENABLED
|
||||||
can_buzzer_update();
|
can_buzzer_update();
|
||||||
#endif
|
#endif
|
||||||
#ifdef HAL_GPIO_PIN_SAFE_LED
|
#ifdef HAL_GPIO_PIN_SAFE_LED
|
||||||
|
@ -977,6 +977,7 @@ class sitl_periph_universal(sitl_periph):
|
|||||||
AP_PERIPH_RTC_ENABLED = 0,
|
AP_PERIPH_RTC_ENABLED = 0,
|
||||||
AP_PERIPH_RCIN_ENABLED = 0,
|
AP_PERIPH_RCIN_ENABLED = 0,
|
||||||
AP_PERIPH_NETWORKING_ENABLED = 0,
|
AP_PERIPH_NETWORKING_ENABLED = 0,
|
||||||
|
AP_PERIPH_NOTIFY_ENABLED = 0,
|
||||||
)
|
)
|
||||||
|
|
||||||
class sitl_periph_gps(sitl_periph):
|
class sitl_periph_gps(sitl_periph):
|
||||||
@ -1004,6 +1005,7 @@ class sitl_periph_gps(sitl_periph):
|
|||||||
AP_PERIPH_RPM_STREAM_ENABLED = 0,
|
AP_PERIPH_RPM_STREAM_ENABLED = 0,
|
||||||
AP_PERIPH_AIRSPEED_ENABLED = 0,
|
AP_PERIPH_AIRSPEED_ENABLED = 0,
|
||||||
AP_PERIPH_NETWORKING_ENABLED = 0,
|
AP_PERIPH_NETWORKING_ENABLED = 0,
|
||||||
|
AP_PERIPH_NOTIFY_ENABLED = 0,
|
||||||
)
|
)
|
||||||
|
|
||||||
class sitl_periph_battmon(sitl_periph):
|
class sitl_periph_battmon(sitl_periph):
|
||||||
@ -1031,6 +1033,7 @@ class sitl_periph_battmon(sitl_periph):
|
|||||||
AP_PERIPH_RPM_STREAM_ENABLED = 0,
|
AP_PERIPH_RPM_STREAM_ENABLED = 0,
|
||||||
AP_PERIPH_AIRSPEED_ENABLED = 0,
|
AP_PERIPH_AIRSPEED_ENABLED = 0,
|
||||||
AP_PERIPH_NETWORKING_ENABLED = 0,
|
AP_PERIPH_NETWORKING_ENABLED = 0,
|
||||||
|
AP_PERIPH_NOTIFY_ENABLED = 0,
|
||||||
)
|
)
|
||||||
|
|
||||||
class esp32(Board):
|
class esp32(Board):
|
||||||
|
Loading…
Reference in New Issue
Block a user