2020-09-12 16:00:22 -03:00
# pragma once
2019-05-26 22:46:41 -03:00
# include <AP_HAL/AP_HAL.h>
# 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>
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>
2020-09-03 08:47:34 -03:00
# include <AP_MSP/AP_MSP.h>
# include <AP_MSP/msp.h>
2019-10-25 22:46:22 -03:00
# include "../AP_Bootloader/app_comms.h"
2020-02-14 01:18:20 -04:00
# include "hwing_esc.h"
2019-10-18 21:28:09 -03:00
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
# ifndef HAL_PERIPH_ENABLE_RC_OUT
# 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
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
/*
app descriptor compatible with MissionPlanner
*/
extern const struct app_descriptor app_descriptor ;
2019-10-18 21:28:09 -03:00
2019-05-26 22:46:41 -03:00
class AP_Periph_FW {
public :
void init ( ) ;
void update ( ) ;
Parameters g ;
void can_start ( ) ;
void can_update ( ) ;
void can_mag_update ( ) ;
void can_gps_update ( ) ;
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 ( ) ;
2019-05-26 22:46:41 -03:00
void load_parameters ( ) ;
2020-12-21 20:27:53 -04:00
void prepare_reboot ( ) ;
2019-05-26 22:46:41 -03:00
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
2019-05-26 22:46:41 -03:00
AP_SerialManager serial_manager ;
# ifdef HAL_PERIPH_ENABLE_GPS
AP_GPS gps ;
# endif
# 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
2020-11-21 01:29:10 -04:00
# ifdef HAL_PERIPH_ENABLE_BATTERY
struct AP_Periph_Battery {
void handle_battery_failsafe ( const char * type_str , const int8_t action ) { }
AP_BattMonitor lib { 0 , FUNCTOR_BIND_MEMBER ( & AP_Periph_FW : : AP_Periph_Battery : : handle_battery_failsafe , void , const char * , const int8_t ) , nullptr } ;
uint32_t last_read_ms ;
uint32_t last_can_send_ms ;
} battery ;
# endif
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 ;
} 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 ;
# 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
# ifdef HAL_PERIPH_ENABLE_RC_OUT
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
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 ) ;
void rcout_srv ( const uint8_t actuator_id , const float command_value ) ;
void rcout_update ( ) ;
void rcout_handle_safety_state ( uint8_t safety_state ) ;
# 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 ;
# 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 [ ] ;
uint32_t last_mag_update_ms ;
uint32_t last_gps_update_ms ;
uint32_t last_baro_update_ms ;
2019-10-03 08:02:56 -03:00
uint32_t last_airspeed_update_ms ;
2020-11-29 19:14:56 -04:00
// show stack as DEBUG msgs
void show_stack_free ( ) ;
2019-05-26 22:46:41 -03:00
} ;
extern AP_Periph_FW periph ;
extern " C " {
void can_printf ( const char * fmt , . . . ) ;
}