2020-09-12 16:00:22 -03:00
# pragma once
2019-05-26 22:46:41 -03:00
# include <AP_HAL/AP_HAL.h>
2023-08-26 06:53:59 -03:00
# include <canard.h>
2019-05-26 22:46:41 -03:00
# include <AP_Param/AP_Param.h>
# include <AP_GPS/AP_GPS.h>
# include <AP_Compass/AP_Compass.h>
# include <AP_Baro/AP_Baro.h>
2020-12-12 05:08:45 -04:00
# include "SRV_Channel/SRV_Channel.h"
2020-12-29 01:06:44 -04:00
# include <AP_Notify/AP_Notify.h>
2021-05-19 23:34:15 -03:00
# include <AP_Logger/AP_Logger.h>
2020-11-21 01:29:10 -04:00
# include <AP_BattMonitor/AP_BattMonitor.h>
2019-10-03 08:02:56 -03:00
# include <AP_Airspeed/AP_Airspeed.h>
2019-10-19 01:36:14 -03:00
# include <AP_RangeFinder/AP_RangeFinder.h>
2022-09-27 16:45:07 -03:00
# include <AP_Proximity/AP_Proximity.h>
2022-06-03 08:00:14 -03:00
# include <AP_EFI/AP_EFI.h>
2023-03-16 21:25:56 -03:00
# include <AP_KDECAN/AP_KDECAN.h>
2020-09-03 08:47:34 -03:00
# include <AP_MSP/AP_MSP.h>
# include <AP_MSP/msp.h>
2022-09-02 18:41:38 -03:00
# include <AP_TemperatureSensor/AP_TemperatureSensor.h>
2019-10-25 22:46:22 -03:00
# include "../AP_Bootloader/app_comms.h"
2022-08-11 05:03:47 -03:00
# include <AP_CheckFirmware/AP_CheckFirmware.h>
2020-02-14 01:18:20 -04:00
# include "hwing_esc.h"
2023-04-18 06:44:06 -03:00
# include <AP_CANManager/AP_CAN.h>
# include <AP_CANManager/AP_SLCANIface.h>
2021-09-17 11:33:17 -03:00
# include <AP_Scripting/AP_Scripting.h>
2022-02-21 00:40:40 -04:00
# include <AP_HAL/CANIface.h>
2022-06-01 01:46:16 -03:00
# include <AP_Stats/AP_Stats.h>
2023-07-06 14:46:05 -03:00
# include <AP_Networking/AP_Networking.h>
2023-08-02 18:34:40 -03:00
# include <AP_RPM/AP_RPM.h>
2023-05-02 23:33:55 -03:00
# include <AP_SerialManager/AP_SerialManager.h>
2023-05-03 19:38:38 -03:00
# include <AP_ESC_Telem/AP_ESC_Telem_config.h>
# if HAL_WITH_ESC_TELEM
# include <AP_ESC_Telem/AP_ESC_Telem.h>
# endif
2023-05-18 05:20:22 -03:00
# include <AP_RCProtocol/AP_RCProtocol_config.h>
2023-08-15 19:13:02 -03:00
# include "rc_in.h"
2023-08-25 06:50:15 -03:00
# include "batt_balance.h"
2023-01-31 19:16:14 -04:00
# include <AP_NMEA_Output/AP_NMEA_Output.h>
# if HAL_NMEA_OUTPUT_ENABLED && !(HAL_GCS_ENABLED && defined(HAL_PERIPH_ENABLE_GPS))
// Needs SerialManager + (AHRS or GPS)
# error "AP_NMEA_Output requires Serial / GCS and either AHRS or GPS. Needs HAL_GCS_ENABLED and HAL_PERIPH_ENABLE_GPS"
# endif
2021-08-18 08:42:18 -03:00
# if HAL_GCS_ENABLED
2021-06-20 03:02:12 -03:00
# include "GCS_MAVLink.h"
# endif
2021-03-02 14:49:09 -04:00
# include "esc_apd_telem.h"
2020-12-29 01:06:44 -04:00
# if defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_NCP5623_BGR_LED_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_TOSHIBA_LED_WITHOUT_NOTIFY)
# define AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
2019-10-18 21:28:09 -03:00
# endif
2020-12-29 01:06:44 -04:00
# ifdef HAL_PERIPH_ENABLE_NOTIFY
2021-09-17 11:33:17 -03:00
# if !defined(HAL_PERIPH_ENABLE_RC_OUT) && !defined(HAL_PERIPH_NOTIFY_WITHOUT_RCOUT)
2020-12-29 01:06:44 -04:00
# error "HAL_PERIPH_ENABLE_NOTIFY requires HAL_PERIPH_ENABLE_RC_OUT"
# endif
# 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"
# endif
# 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"
# endif
# 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"
# endif
# endif
2023-09-13 16:27:37 -03:00
# ifndef AP_PERIPH_SAFETY_SWITCH_ENABLED
# define AP_PERIPH_SAFETY_SWITCH_ENABLED defined(HAL_PERIPH_ENABLE_RC_OUT)
# endif
2023-05-09 19:52:15 -03:00
# ifndef HAL_PERIPH_CAN_MIRROR
# define HAL_PERIPH_CAN_MIRROR 0
# endif
2019-05-26 22:46:41 -03:00
# include "Parameters.h"
2020-09-12 16:00:22 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
void stm32_watchdog_init ( ) ;
void stm32_watchdog_pat ( ) ;
# endif
2019-10-20 23:35:01 -03:00
/*
2022-09-02 23:22:06 -03:00
app descriptor for firmware checking
2019-10-20 23:35:01 -03:00
*/
2022-09-02 23:22:06 -03:00
extern const app_descriptor_t app_descriptor ;
2019-10-18 21:28:09 -03:00
2022-03-08 12:16:48 -04:00
extern " C " {
void can_printf ( const char * fmt , . . . ) FMT_PRINTF ( 1 , 2 ) ;
}
2023-06-26 06:55:54 -03:00
struct CanardInstance ;
struct CanardRxTransfer ;
2023-08-26 06:53:59 -03:00
# define MAKE_TRANSFER_DESCRIPTOR(data_type_id, transfer_type, src_node_id, dst_node_id) \
( ( ( uint32_t ) ( data_type_id ) ) | ( ( ( uint32_t ) ( transfer_type ) ) < < 16U ) | \
( ( ( uint32_t ) ( src_node_id ) ) < < 18U ) | ( ( ( uint32_t ) ( dst_node_id ) ) < < 25U ) )
# ifndef HAL_CAN_POOL_SIZE
# if HAL_CANFD_SUPPORTED
# define HAL_CAN_POOL_SIZE 16000
# elif GPS_MOVING_BASELINE
# define HAL_CAN_POOL_SIZE 8000
# else
# define HAL_CAN_POOL_SIZE 4000
# endif
# endif
2019-05-26 22:46:41 -03:00
class AP_Periph_FW {
public :
2021-05-19 23:34:15 -03:00
AP_Periph_FW ( ) ;
2021-04-30 22:36:42 -03:00
CLASS_NO_COPY ( AP_Periph_FW ) ;
static AP_Periph_FW * get_singleton ( )
{
if ( _singleton = = nullptr ) {
AP_HAL : : panic ( " AP_Periph_FW used before allocation. " ) ;
}
return _singleton ;
}
2019-05-26 22:46:41 -03:00
void init ( ) ;
void update ( ) ;
Parameters g ;
void can_start ( ) ;
void can_update ( ) ;
void can_mag_update ( ) ;
void can_gps_update ( ) ;
2021-07-16 13:16:24 -03:00
void send_moving_baseline_msg ( ) ;
void send_relposheading_msg ( ) ;
2019-05-26 22:46:41 -03:00
void can_baro_update ( ) ;
2019-10-03 08:02:56 -03:00
void can_airspeed_update ( ) ;
2019-10-19 01:36:14 -03:00
void can_rangefinder_update ( ) ;
2020-11-21 01:29:10 -04:00
void can_battery_update ( ) ;
2023-09-27 20:31:50 -03:00
void can_battery_send_cells ( uint8_t instance ) ;
2022-09-27 16:45:07 -03:00
void can_proximity_update ( ) ;
2023-08-26 06:53:59 -03:00
void can_buzzer_update ( void ) ;
void can_safety_button_update ( void ) ;
void can_safety_LED_update ( void ) ;
2019-05-26 22:46:41 -03:00
void load_parameters ( ) ;
2020-12-21 20:27:53 -04:00
void prepare_reboot ( ) ;
2021-05-17 14:26:34 -03:00
bool canfdout ( ) const { return ( g . can_fdmode = = 1 ) ; }
2019-05-26 22:46:41 -03:00
2022-06-03 08:00:14 -03:00
# ifdef HAL_PERIPH_ENABLE_EFI
void can_efi_update ( ) ;
# endif
2020-12-21 20:27:53 -04:00
# ifdef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT
2020-12-15 21:27:28 -04:00
void check_for_serial_reboot_cmd ( const int8_t serial_index ) ;
2020-12-21 20:27:53 -04:00
# endif
2020-12-15 21:27:28 -04:00
2021-04-30 22:36:42 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
static ChibiOS : : CANIface * can_iface_periph [ HAL_NUM_CAN_IFACES ] ;
# elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
static HALSITL : : CANIface * can_iface_periph [ HAL_NUM_CAN_IFACES ] ;
# endif
2023-03-10 20:46:34 -04:00
# if AP_CAN_SLCAN_ENABLED
2022-10-07 00:19:55 -03:00
static SLCAN : : CANIface slcan_interface ;
# endif
2019-05-26 22:46:41 -03:00
AP_SerialManager serial_manager ;
2022-06-01 01:46:16 -03:00
# if AP_STATS_ENABLED
AP_Stats node_stats ;
# endif
2019-05-26 22:46:41 -03:00
# ifdef HAL_PERIPH_ENABLE_GPS
AP_GPS gps ;
2021-07-16 13:16:24 -03:00
# if HAL_NUM_CAN_IFACES >= 2
int8_t gps_mb_can_port = - 1 ;
# endif
2019-05-26 22:46:41 -03:00
# endif
2023-01-31 19:16:14 -04:00
# if HAL_NMEA_OUTPUT_ENABLED
AP_NMEA_Output nmea ;
# endif
2019-05-26 22:46:41 -03:00
# ifdef HAL_PERIPH_ENABLE_MAG
Compass compass ;
# endif
# ifdef HAL_PERIPH_ENABLE_BARO
AP_Baro baro ;
# endif
2019-10-02 06:04:44 -03:00
2023-08-02 18:34:40 -03:00
# ifdef HAL_PERIPH_ENABLE_RPM
AP_RPM rpm_sensor ;
uint32_t rpm_last_update_ms ;
# endif
2020-11-21 01:29:10 -04:00
# ifdef HAL_PERIPH_ENABLE_BATTERY
2023-08-22 20:00:26 -03:00
void handle_battery_failsafe ( const char * type_str , const int8_t action ) { }
AP_BattMonitor battery_lib { 0 , FUNCTOR_BIND_MEMBER ( & AP_Periph_FW : : handle_battery_failsafe , void , const char * , const int8_t ) , nullptr } ;
struct {
2020-11-21 01:29:10 -04:00
uint32_t last_read_ms ;
uint32_t last_can_send_ms ;
} battery ;
# endif
2021-04-30 22:36:42 -03:00
# if HAL_NUM_CAN_IFACES >= 2
// This allows you to change the protocol and it continues to use the one at boot.
// Without this, changing away from UAVCAN causes loss of comms and you can't
2021-06-19 13:19:07 -03:00
// change the rest of your params or verify it succeeded.
2023-04-18 06:44:06 -03:00
AP_CAN : : Protocol can_protocol_cached [ HAL_NUM_CAN_IFACES ] ;
2021-04-30 22:36:42 -03:00
# endif
2020-11-21 01:29:10 -04:00
2020-09-03 08:47:34 -03:00
# ifdef HAL_PERIPH_ENABLE_MSP
struct {
AP_MSP msp ;
MSP : : msp_port_t port ;
uint32_t last_gps_ms ;
uint32_t last_baro_ms ;
uint32_t last_mag_ms ;
2020-10-24 05:52:29 -03:00
uint32_t last_airspeed_ms ;
2020-09-03 08:47:34 -03:00
} msp ;
void msp_init ( AP_HAL : : UARTDriver * _uart ) ;
void msp_sensor_update ( void ) ;
void send_msp_packet ( uint16_t cmd , void * p , uint16_t size ) ;
void send_msp_GPS ( void ) ;
void send_msp_compass ( void ) ;
void send_msp_baro ( void ) ;
2020-10-24 05:52:29 -03:00
void send_msp_airspeed ( void ) ;
2020-09-03 08:47:34 -03:00
# endif
2019-10-02 06:04:44 -03:00
# ifdef HAL_PERIPH_ENABLE_ADSB
void adsb_init ( ) ;
void adsb_update ( ) ;
void can_send_ADSB ( struct __mavlink_adsb_vehicle_t & msg ) ;
struct {
mavlink_message_t msg ;
mavlink_status_t status ;
2023-09-29 01:13:50 -03:00
uint32_t last_heartbeat_ms ;
2019-10-02 06:04:44 -03:00
} adsb ;
# endif
2019-10-03 08:02:56 -03:00
# ifdef HAL_PERIPH_ENABLE_AIRSPEED
AP_Airspeed airspeed ;
# endif
2019-10-19 01:36:14 -03:00
# ifdef HAL_PERIPH_ENABLE_RANGEFINDER
RangeFinder rangefinder ;
2022-05-27 20:27:39 -03:00
uint32_t last_sample_ms ;
2019-10-19 01:36:14 -03:00
# endif
2019-12-19 02:21:25 -04:00
2023-08-26 06:53:59 -03:00
# ifdef HAL_PERIPH_ENABLE_PROXIMITY
2022-09-27 16:45:07 -03:00
AP_Proximity proximity ;
# endif
2019-12-19 02:21:25 -04:00
# ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT
void pwm_irq_handler ( uint8_t pin , bool pin_state , uint32_t timestamp ) ;
void pwm_hardpoint_init ( ) ;
void pwm_hardpoint_update ( ) ;
struct {
uint8_t last_state ;
uint32_t last_ts_us ;
uint32_t last_send_ms ;
uint16_t pwm_value ;
2019-12-19 03:46:03 -04:00
uint16_t highest_pwm ;
2019-12-19 02:21:25 -04:00
} pwm_hardpoint ;
# endif
2020-02-14 01:18:20 -04:00
# ifdef HAL_PERIPH_ENABLE_HWESC
HWESC_Telem hwesc_telem ;
void hwesc_telem_update ( ) ;
# endif
2020-12-12 05:08:45 -04:00
2022-06-03 08:00:14 -03:00
# ifdef HAL_PERIPH_ENABLE_EFI
AP_EFI efi ;
uint32_t efi_update_ms ;
# endif
2023-03-16 21:25:56 -03:00
# if AP_KDECAN_ENABLED
AP_KDECAN kdecan ;
# endif
2021-03-02 14:49:09 -04:00
# ifdef HAL_PERIPH_ENABLE_ESC_APD
ESC_APD_Telem * apd_esc_telem [ APD_ESC_INSTANCES ] ;
void apd_esc_telem_update ( ) ;
# endif
2023-03-16 21:25:56 -03:00
2020-12-12 05:08:45 -04:00
# ifdef HAL_PERIPH_ENABLE_RC_OUT
2021-12-06 22:47:50 -04:00
# if HAL_WITH_ESC_TELEM
AP_ESC_Telem esc_telem ;
uint32_t last_esc_telem_update_ms ;
2021-12-08 19:52:38 -04:00
void esc_telem_update ( ) ;
2022-09-05 14:07:19 -03:00
uint32_t esc_telem_update_period_ms ;
2021-12-06 22:47:50 -04:00
# endif
2020-12-12 05:08:45 -04:00
SRV_Channels servo_channels ;
2020-12-29 01:06:44 -04:00
bool rcout_has_new_data_to_update ;
2020-12-12 05:08:45 -04:00
2022-11-28 00:45:59 -04:00
uint32_t last_esc_raw_command_ms ;
uint8_t last_esc_num_channels ;
2020-12-12 05:08:45 -04:00
void rcout_init ( ) ;
2020-12-21 20:27:53 -04:00
void rcout_init_1Hz ( ) ;
2020-12-12 05:08:45 -04:00
void rcout_esc ( int16_t * rc , uint8_t num_channels ) ;
2022-09-12 00:27:22 -03:00
void rcout_srv_unitless ( const uint8_t actuator_id , const float command_value ) ;
void rcout_srv_PWM ( const uint8_t actuator_id , const float command_value ) ;
2020-12-12 05:08:45 -04:00
void rcout_update ( ) ;
void rcout_handle_safety_state ( uint8_t safety_state ) ;
# endif
2023-05-18 05:20:22 -03:00
# ifdef HAL_PERIPH_ENABLE_RCIN
void rcin_init ( ) ;
void rcin_update ( ) ;
void can_send_RCInput ( uint8_t quality , uint16_t * values , uint8_t nvalues , bool in_failsafe , bool quality_valid ) ;
bool rcin_initialised ;
uint32_t rcin_last_sent_RCInput_ms ;
const char * rcin_rc_protocol ; // protocol currently being decoded
2023-08-15 19:13:02 -03:00
Parameters_RCIN g_rcin ;
2023-05-18 05:20:22 -03:00
# endif
2023-08-25 06:50:15 -03:00
# ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE
void batt_balance_update ( ) ;
BattBalance battery_balance ;
# endif
2022-09-02 18:41:38 -03:00
# if AP_TEMPERATURE_SENSOR_ENABLED
AP_TemperatureSensor temperature_sensor ;
# endif
2020-12-29 01:06:44 -04:00
# if defined(HAL_PERIPH_ENABLE_NOTIFY) || defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY)
void update_rainbow ( ) ;
# endif
# ifdef HAL_PERIPH_ENABLE_NOTIFY
// notification object for LEDs, buzzers etc
AP_Notify notify ;
2021-09-17 11:33:17 -03:00
uint64_t vehicle_state = 1 ; // default to initialisation
float yaw_earth ;
uint32_t last_vehicle_state ;
// Handled under LUA script to control LEDs
float get_yaw_earth ( ) { return yaw_earth ; }
uint32_t get_vehicle_state ( ) { return vehicle_state ; }
2021-11-15 01:08:36 -04:00
# elif defined(AP_SCRIPTING_ENABLED)
2021-09-17 11:33:17 -03:00
// create dummy methods for the case when the user doesn't want to use the notify object
float get_yaw_earth ( ) { return 0.0 ; }
uint32_t get_vehicle_state ( ) { return 0.0 ; }
# endif
2021-11-15 01:08:36 -04:00
# if AP_SCRIPTING_ENABLED
2021-09-17 11:33:17 -03:00
AP_Scripting scripting ;
2020-12-29 01:06:44 -04:00
# endif
2021-05-19 23:34:15 -03:00
# if HAL_LOGGING_ENABLED
static const struct LogStructure log_structure [ ] ;
AP_Logger logger ;
# endif
2023-08-02 21:50:27 -03:00
# ifdef HAL_PERIPH_ENABLE_NETWORKING
2023-07-06 14:46:05 -03:00
AP_Networking networking ;
# endif
2023-10-08 00:46:27 -03:00
# ifdef HAL_PERIPH_ENABLE_RTC
AP_RTC rtc ;
# endif
2021-08-18 08:42:18 -03:00
# if HAL_GCS_ENABLED
2021-06-20 03:02:12 -03:00
GCS_Periph _gcs ;
# endif
2019-05-26 22:46:41 -03:00
// setup the var_info table
AP_Param param_loader { var_info } ;
static const AP_Param : : Info var_info [ ] ;
2023-10-03 15:04:22 -03:00
# ifdef HAL_PERIPH_ENABLE_EFI
uint32_t last_efi_update_ms ;
# endif
# ifdef HAL_PERIPH_ENABLE_MAG
2019-05-26 22:46:41 -03:00
uint32_t last_mag_update_ms ;
2023-10-03 15:04:22 -03:00
# endif
# ifdef HAL_PERIPH_ENABLE_GPS
2019-05-26 22:46:41 -03:00
uint32_t last_gps_update_ms ;
2022-12-15 04:05:58 -04:00
uint32_t last_gps_yaw_ms ;
2023-10-03 15:04:22 -03:00
# endif
2022-12-15 04:05:58 -04:00
uint32_t last_relposheading_ms ;
2023-10-03 15:04:22 -03:00
# ifdef HAL_PERIPH_ENABLE_BARO
2019-05-26 22:46:41 -03:00
uint32_t last_baro_update_ms ;
2023-10-03 15:04:22 -03:00
# endif
# ifdef HAL_PERIPH_ENABLE_AIRSPEED
2019-10-03 08:02:56 -03:00
uint32_t last_airspeed_update_ms ;
2023-10-03 15:04:22 -03:00
# endif
# ifdef HAL_PERIPH_ENABLE_GPS
2022-01-18 06:51:00 -04:00
bool saw_gps_lock_once ;
2023-10-03 15:04:22 -03:00
# endif
2020-11-29 19:14:56 -04:00
2021-04-30 22:36:42 -03:00
static AP_Periph_FW * _singleton ;
2023-07-07 04:36:52 -03:00
enum class DebugOptions {
SHOW_STACK = 0 ,
AUTOREBOOT = 1 ,
ENABLE_STATS = 2 ,
2022-03-08 04:51:27 -04:00
} ;
2023-07-07 04:36:52 -03:00
// check if an option is set
bool debug_option_is_set ( const DebugOptions option ) const {
return ( uint8_t ( g . debug . get ( ) ) & ( 1U < < uint8_t ( option ) ) ) ! = 0 ;
}
2020-11-29 19:14:56 -04:00
// show stack as DEBUG msgs
void show_stack_free ( ) ;
2021-07-12 12:59:31 -03:00
static bool no_iface_finished_dna ;
2022-03-08 12:16:48 -04:00
static constexpr auto can_printf = : : can_printf ;
2023-07-03 21:12:19 -03:00
2023-08-26 06:53:59 -03:00
bool canard_broadcast ( uint64_t data_type_signature ,
uint16_t data_type_id ,
uint8_t priority ,
const void * payload ,
uint16_t payload_len ) ;
void onTransferReceived ( CanardInstance * canard_instance ,
CanardRxTransfer * transfer ) ;
bool shouldAcceptTransfer ( const CanardInstance * canard_instance ,
uint64_t * out_data_type_signature ,
uint16_t data_type_id ,
CanardTransferType transfer_type ,
uint8_t source_node_id ) ;
2023-06-26 06:55:54 -03:00
# if AP_UART_MONITOR_ENABLED
2023-07-31 07:39:12 -03:00
void handle_tunnel_Targetted ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
2023-06-26 06:55:54 -03:00
void send_serial_monitor_data ( ) ;
int8_t get_default_tunnel_serial_port ( void ) const ;
struct {
ByteBuffer * buffer ;
uint32_t last_request_ms ;
AP_HAL : : UARTDriver * uart ;
int8_t uart_num ;
uint8_t node_id ;
uint8_t protocol ;
uint32_t baudrate ;
bool locked ;
} uart_monitor ;
# endif
2023-08-17 17:27:55 -03:00
2023-08-26 06:53:59 -03:00
// handlers for incoming messages
void handle_get_node_info ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void handle_param_getset ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void handle_param_executeopcode ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void handle_begin_firmware_update ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void handle_allocation_response ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void handle_safety_state ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void handle_arming_status ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void handle_RTCMStream ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void handle_MovingBaselineData ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void handle_esc_rawcommand ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void handle_act_command ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void handle_beep_command ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void handle_lightscommand ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void handle_notify_state ( CanardInstance * canard_instance , CanardRxTransfer * transfer ) ;
void process1HzTasks ( uint64_t timestamp_usec ) ;
void processTx ( void ) ;
void processRx ( void ) ;
2023-05-09 19:52:15 -03:00
# if HAL_PERIPH_CAN_MIRROR
void processMirror ( void ) ;
# endif // HAL_PERIPH_CAN_MIRROR
2023-08-26 06:53:59 -03:00
void cleanup_stale_transactions ( uint64_t & timestamp_usec ) ;
void update_rx_protocol_stats ( int16_t res ) ;
void node_status_send ( void ) ;
bool can_do_dna ( ) ;
uint8_t * get_tid_ptr ( uint32_t transfer_desc ) ;
uint16_t pool_peak_percent ( ) ;
void set_rgb_led ( uint8_t red , uint8_t green , uint8_t blue ) ;
struct dronecan_protocol_t {
CanardInstance canard ;
uint32_t canard_memory_pool [ HAL_CAN_POOL_SIZE / sizeof ( uint32_t ) ] ;
struct tid_map {
uint32_t transfer_desc ;
uint8_t tid ;
tid_map * next ;
} * tid_map_head ;
/*
* Variables used for dynamic node ID allocation .
* RTFM at http : //uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation
*/
uint32_t send_next_node_id_allocation_request_at_ms ; ///< When the next node ID allocation request should be sent
uint8_t node_id_allocation_unique_id_offset ; ///< Depends on the stage of the next request
uint8_t tx_fail_count ;
uint8_t dna_interface = 1 ;
} dronecan ;
2023-08-17 17:27:55 -03:00
# if AP_SIM_ENABLED
SITL : : SIM sitl ;
2023-10-03 23:00:27 -03:00
# endif
2023-08-17 17:27:55 -03:00
# if AP_AHRS_ENABLED
AP_AHRS ahrs ;
# endif
2019-05-26 22:46:41 -03:00
} ;
2023-09-01 22:49:57 -03:00
# ifndef CAN_APP_NODE_NAME
# define CAN_APP_NODE_NAME "org.ardupilot." CHIBIOS_BOARD_NAME
# endif
2021-04-30 22:36:42 -03:00
namespace AP
{
AP_Periph_FW & periph ( ) ;
}
2019-05-26 22:46:41 -03:00
extern AP_Periph_FW periph ;