mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-01 03:04:04 -04:00
Tools: use new AP_PERIPH_RELAY_ENABLED define
This commit is contained in:
parent
e696a83371
commit
873abe3fd3
@ -304,7 +304,7 @@ void AP_Periph_FW::init()
|
|||||||
notify.init();
|
notify.init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_RELAY
|
#if AP_PERIPH_RELAY_ENABLED
|
||||||
relay.init();
|
relay.init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -47,7 +47,7 @@
|
|||||||
#endif
|
#endif
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_RELAY
|
#if AP_PERIPH_RELAY_ENABLED
|
||||||
#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT
|
#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT
|
||||||
#error "Relay and PWM_HARDPOINT both use hardpoint message"
|
#error "Relay and PWM_HARDPOINT both use hardpoint message"
|
||||||
#endif
|
#endif
|
||||||
@ -437,7 +437,7 @@ public:
|
|||||||
GCS_Periph _gcs;
|
GCS_Periph _gcs;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_RELAY
|
#if AP_PERIPH_RELAY_ENABLED
|
||||||
AP_Relay relay;
|
AP_Relay relay;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -677,7 +677,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||||||
GOBJECT(rtc, "RTC", AP_RTC),
|
GOBJECT(rtc, "RTC", AP_RTC),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_RELAY
|
#if AP_PERIPH_RELAY_ENABLED
|
||||||
// @Group: RELAY
|
// @Group: RELAY
|
||||||
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
|
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
|
||||||
GOBJECT(relay, "RELAY", AP_Relay),
|
GOBJECT(relay, "RELAY", AP_Relay),
|
||||||
|
@ -880,7 +880,7 @@ void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance,
|
|||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_RELAY
|
#if AP_PERIPH_RELAY_ENABLED
|
||||||
case UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID:
|
case UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID:
|
||||||
handle_hardpoint_command(canard_instance, transfer);
|
handle_hardpoint_command(canard_instance, transfer);
|
||||||
break;
|
break;
|
||||||
@ -995,7 +995,7 @@ bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance,
|
|||||||
*out_data_type_signature = ARDUPILOT_INDICATION_NOTIFYSTATE_SIGNATURE;
|
*out_data_type_signature = ARDUPILOT_INDICATION_NOTIFYSTATE_SIGNATURE;
|
||||||
return true;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
#ifdef HAL_PERIPH_ENABLE_RELAY
|
#if AP_PERIPH_RELAY_ENABLED
|
||||||
case UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID:
|
case UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID:
|
||||||
*out_data_type_signature = UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_SIGNATURE;
|
*out_data_type_signature = UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_SIGNATURE;
|
||||||
return true;
|
return true;
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
#include "AP_Periph.h"
|
#include "AP_Periph.h"
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_RELAY
|
#if AP_PERIPH_RELAY_ENABLED
|
||||||
|
|
||||||
#include <dronecan_msgs.h>
|
#include <dronecan_msgs.h>
|
||||||
|
|
||||||
|
@ -955,6 +955,7 @@ class sitl_periph_universal(sitl_periph):
|
|||||||
AP_PERIPH_GPS_ENABLED = 1,
|
AP_PERIPH_GPS_ENABLED = 1,
|
||||||
AP_PERIPH_AIRSPEED_ENABLED = 1,
|
AP_PERIPH_AIRSPEED_ENABLED = 1,
|
||||||
AP_PERIPH_MAG_ENABLED = 1,
|
AP_PERIPH_MAG_ENABLED = 1,
|
||||||
|
AP_PERIPH_RELAY_ENABLED = 0,
|
||||||
AP_PERIPH_BARO_ENABLED = 1,
|
AP_PERIPH_BARO_ENABLED = 1,
|
||||||
AP_PERIPH_IMU_ENABLED = 1,
|
AP_PERIPH_IMU_ENABLED = 1,
|
||||||
AP_PERIPH_RANGEFINDER_ENABLED = 1,
|
AP_PERIPH_RANGEFINDER_ENABLED = 1,
|
||||||
@ -994,6 +995,7 @@ class sitl_periph_gps(sitl_periph):
|
|||||||
AP_PERIPH_BATTERY_ENABLED = 0,
|
AP_PERIPH_BATTERY_ENABLED = 0,
|
||||||
AP_PERIPH_ADSB_ENABLED = 0,
|
AP_PERIPH_ADSB_ENABLED = 0,
|
||||||
AP_PERIPH_GPS_ENABLED = 1,
|
AP_PERIPH_GPS_ENABLED = 1,
|
||||||
|
AP_PERIPH_RELAY_ENABLED = 0,
|
||||||
AP_PERIPH_IMU_ENABLED = 0,
|
AP_PERIPH_IMU_ENABLED = 0,
|
||||||
AP_PERIPH_MAG_ENABLED = 0,
|
AP_PERIPH_MAG_ENABLED = 0,
|
||||||
AP_PERIPH_BATTERY_BALANCE_ENABLED = 0,
|
AP_PERIPH_BATTERY_BALANCE_ENABLED = 0,
|
||||||
@ -1023,6 +1025,7 @@ class sitl_periph_battmon(sitl_periph):
|
|||||||
|
|
||||||
AP_PERIPH_BATTERY_ENABLED = 1,
|
AP_PERIPH_BATTERY_ENABLED = 1,
|
||||||
AP_PERIPH_BATTERY_BALANCE_ENABLED = 0,
|
AP_PERIPH_BATTERY_BALANCE_ENABLED = 0,
|
||||||
|
AP_PERIPH_RELAY_ENABLED = 0,
|
||||||
AP_PERIPH_ADSB_ENABLED = 0,
|
AP_PERIPH_ADSB_ENABLED = 0,
|
||||||
AP_PERIPH_BARO_ENABLED = 0,
|
AP_PERIPH_BARO_ENABLED = 0,
|
||||||
AP_PERIPH_RANGEFINDER_ENABLED = 0,
|
AP_PERIPH_RANGEFINDER_ENABLED = 0,
|
||||||
|
Loading…
Reference in New Issue
Block a user