Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/AP_Periph/AP_Periph.h
Views: 1798
#pragma once12#include <AP_HAL/AP_HAL.h>3#include <canard.h>4#include <AP_Param/AP_Param.h>5#include <AP_GPS/AP_GPS.h>6#include <AP_Compass/AP_Compass.h>7#include <AP_Baro/AP_Baro.h>8#include <AP_InertialSensor/AP_InertialSensor.h>9#include "SRV_Channel/SRV_Channel.h"10#include <AP_Notify/AP_Notify.h>11#include <AP_Logger/AP_Logger.h>12#include <AP_BattMonitor/AP_BattMonitor.h>13#include <AP_Airspeed/AP_Airspeed.h>14#include <AP_RangeFinder/AP_RangeFinder.h>15#include <AP_RangeFinder/AP_RangeFinder_Backend.h>16#include <AP_Proximity/AP_Proximity.h>17#include <AP_EFI/AP_EFI.h>18#include <AP_KDECAN/AP_KDECAN.h>19#include <AP_MSP/AP_MSP.h>20#include <AP_MSP/msp.h>21#include <AP_TemperatureSensor/AP_TemperatureSensor.h>22#include "../AP_Bootloader/app_comms.h"23#include <AP_CheckFirmware/AP_CheckFirmware.h>24#include "hwing_esc.h"25#include <AP_CANManager/AP_CAN.h>26#include <AP_CANManager/AP_SLCANIface.h>27#include <AP_Scripting/AP_Scripting.h>28#include <AP_HAL/CANIface.h>29#include <AP_Stats/AP_Stats.h>30#include <AP_RPM/AP_RPM.h>31#include <AP_SerialManager/AP_SerialManager.h>32#include <AP_ESC_Telem/AP_ESC_Telem_config.h>33#if HAL_WITH_ESC_TELEM34#include <AP_ESC_Telem/AP_ESC_Telem.h>35#endif36#ifdef HAL_PERIPH_ENABLE_RTC37#include <AP_RTC/AP_RTC.h>38#endif39#include <AP_RCProtocol/AP_RCProtocol_config.h>40#include "rc_in.h"41#include "batt_balance.h"42#include "networking.h"43#include "serial_options.h"44#if AP_SIM_ENABLED45#include <SITL/SITL.h>46#endif47#include <AP_AHRS/AP_AHRS.h>4849#ifdef HAL_PERIPH_ENABLE_RELAY50#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT51#error "Relay and PWM_HARDPOINT both use hardpoint message"52#endif53#include <AP_Relay/AP_Relay.h>54#if !AP_RELAY_ENABLED55#error "HAL_PERIPH_ENABLE_RELAY requires AP_RELAY_ENABLED"56#endif57#endif5859#if defined(HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE) && !AP_TEMPERATURE_SENSOR_ENABLED60#error "HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE requires AP_TEMPERATURE_SENSOR_ENABLED"61#endif6263#include <AP_NMEA_Output/AP_NMEA_Output.h>64#if HAL_NMEA_OUTPUT_ENABLED && !(HAL_GCS_ENABLED && defined(HAL_PERIPH_ENABLE_GPS))65// Needs SerialManager + (AHRS or GPS)66#error "AP_NMEA_Output requires Serial/GCS and either AHRS or GPS. Needs HAL_GCS_ENABLED and HAL_PERIPH_ENABLE_GPS"67#endif6869#if HAL_GCS_ENABLED70#include "GCS_MAVLink.h"71#endif7273#include "esc_apd_telem.h"7475#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)76#define AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY77#endif7879#ifdef HAL_PERIPH_ENABLE_NOTIFY80#if !defined(HAL_PERIPH_ENABLE_RC_OUT) && !defined(HAL_PERIPH_NOTIFY_WITHOUT_RCOUT)81#error "HAL_PERIPH_ENABLE_NOTIFY requires HAL_PERIPH_ENABLE_RC_OUT"82#endif83#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY84#error "You cannot enable HAL_PERIPH_ENABLE_NOTIFY and HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY at the same time. Notify already includes it"85#endif86#ifdef AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY87#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"88#endif89#ifdef HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY90#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"91#endif92#endif9394#if defined(HAL_PERIPH_ENABLE_RPM_STREAM) && !defined(HAL_PERIPH_ENABLE_RPM)95#error "HAL_PERIPH_ENABLE_RPM_STREAM requires HAL_PERIPH_ENABLE_RPM"96#endif9798#ifndef AP_PERIPH_SAFETY_SWITCH_ENABLED99#define AP_PERIPH_SAFETY_SWITCH_ENABLED defined(HAL_PERIPH_ENABLE_RC_OUT)100#endif101102#ifndef HAL_PERIPH_CAN_MIRROR103#define HAL_PERIPH_CAN_MIRROR 0104#endif105106#if defined(HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT) && !defined(HAL_DEBUG_BUILD) && !defined(HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_NON_DEBUG)107/* this checking for reboot can lose bytes on GPS modules and other108* serial devices. It is really only relevent on a debug build if you109* really want it for non-debug build then define110* HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_NON_DEBUG in hwdef.dat111*/112#undef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT113#endif114115#include "Parameters.h"116117#if CONFIG_HAL_BOARD == HAL_BOARD_SITL118void stm32_watchdog_init();119void stm32_watchdog_pat();120#endif121/*122app descriptor for firmware checking123*/124extern const app_descriptor_t app_descriptor;125126extern "C" {127void can_vprintf(uint8_t severity, const char *fmt, va_list arg);128void can_printf_severity(uint8_t severity, const char *fmt, ...) FMT_PRINTF(2,3);129void can_printf(const char *fmt, ...) FMT_PRINTF(1,2);130}131132struct CanardInstance;133struct CanardRxTransfer;134135#define MAKE_TRANSFER_DESCRIPTOR(data_type_id, transfer_type, src_node_id, dst_node_id) \136(((uint32_t)(data_type_id)) | (((uint32_t)(transfer_type)) << 16U) | \137(((uint32_t)(src_node_id)) << 18U) | (((uint32_t)(dst_node_id)) << 25U))138139#ifndef HAL_CAN_POOL_SIZE140#if HAL_CANFD_SUPPORTED141#define HAL_CAN_POOL_SIZE 16000142#elif GPS_MOVING_BASELINE143#define HAL_CAN_POOL_SIZE 8000144#else145#define HAL_CAN_POOL_SIZE 4000146#endif147#endif148149class AP_Periph_FW {150public:151AP_Periph_FW();152153CLASS_NO_COPY(AP_Periph_FW);154155static AP_Periph_FW* get_singleton()156{157if (_singleton == nullptr) {158AP_HAL::panic("AP_Periph_FW used before allocation.");159}160return _singleton;161}162163void init();164void update();165166Parameters g;167168void can_start();169void can_update();170void can_mag_update();171void can_gps_update();172void send_moving_baseline_msg();173void send_relposheading_msg();174void can_baro_update();175void can_airspeed_update();176#ifdef HAL_PERIPH_ENABLE_IMU177void can_imu_update();178#endif179180#ifdef HAL_PERIPH_ENABLE_RANGEFINDER181void can_rangefinder_update();182#endif183void can_battery_update();184void can_battery_send_cells(uint8_t instance);185void can_proximity_update();186void can_buzzer_update(void);187void can_safety_button_update(void);188void can_safety_LED_update(void);189190void load_parameters();191void prepare_reboot();192bool canfdout() const { return (g.can_fdmode == 1); }193194#ifdef HAL_PERIPH_ENABLE_EFI195void can_efi_update();196#endif197198#ifdef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT199void check_for_serial_reboot_cmd(const int8_t serial_index);200#endif201202#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS203static ChibiOS::CANIface* can_iface_periph[HAL_NUM_CAN_IFACES];204#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL205static HALSITL::CANIface* can_iface_periph[HAL_NUM_CAN_IFACES];206#endif207208#if AP_CAN_SLCAN_ENABLED209static SLCAN::CANIface slcan_interface;210#endif211212AP_SerialManager serial_manager;213214#if AP_STATS_ENABLED215AP_Stats node_stats;216#endif217218#ifdef HAL_PERIPH_ENABLE_GPS219AP_GPS gps;220#if HAL_NUM_CAN_IFACES >= 2221int8_t gps_mb_can_port = -1;222#endif223#endif224225#if HAL_NMEA_OUTPUT_ENABLED226AP_NMEA_Output nmea;227#endif228229#ifdef HAL_PERIPH_ENABLE_MAG230Compass compass;231#endif232233#ifdef HAL_PERIPH_ENABLE_BARO234AP_Baro baro;235#endif236237#ifdef HAL_PERIPH_ENABLE_IMU238AP_InertialSensor imu;239#endif240241#ifdef HAL_PERIPH_ENABLE_RPM242AP_RPM rpm_sensor;243uint32_t rpm_last_update_ms;244#ifdef HAL_PERIPH_ENABLE_RPM_STREAM245void rpm_sensor_send();246uint32_t rpm_last_send_ms;247uint8_t rpm_last_sent_index;248#endif249#endif // HAL_PERIPH_ENABLE_RPM250251#ifdef HAL_PERIPH_ENABLE_BATTERY252void handle_battery_failsafe(const char* type_str, const int8_t action) { }253AP_BattMonitor battery_lib{0, FUNCTOR_BIND_MEMBER(&AP_Periph_FW::handle_battery_failsafe, void, const char*, const int8_t), nullptr};254struct {255uint32_t last_read_ms;256uint32_t last_can_send_ms;257} battery;258#endif259260#if HAL_NUM_CAN_IFACES >= 2261// This allows you to change the protocol and it continues to use the one at boot.262// Without this, changing away from UAVCAN causes loss of comms and you can't263// change the rest of your params or verify it succeeded.264AP_CAN::Protocol can_protocol_cached[HAL_NUM_CAN_IFACES];265#endif266267#ifdef HAL_PERIPH_ENABLE_MSP268struct {269AP_MSP msp;270MSP::msp_port_t port;271uint32_t last_gps_ms;272uint32_t last_baro_ms;273uint32_t last_mag_ms;274uint32_t last_airspeed_ms;275} msp;276void msp_init(AP_HAL::UARTDriver *_uart);277void msp_sensor_update(void);278void send_msp_packet(uint16_t cmd, void *p, uint16_t size);279void send_msp_GPS(void);280void send_msp_compass(void);281void send_msp_baro(void);282void send_msp_airspeed(void);283#endif284285#ifdef HAL_PERIPH_ENABLE_ADSB286void adsb_init();287void adsb_update();288void can_send_ADSB(struct __mavlink_adsb_vehicle_t &msg);289struct {290mavlink_message_t msg;291mavlink_status_t status;292uint32_t last_heartbeat_ms;293} adsb;294#endif295296#ifdef HAL_PERIPH_ENABLE_AIRSPEED297AP_Airspeed airspeed;298#endif299300#ifdef HAL_PERIPH_ENABLE_RANGEFINDER301RangeFinder rangefinder;302uint32_t last_rangefinder_update_ms;303uint32_t last_rangefinder_sample_ms[RANGEFINDER_MAX_INSTANCES];304#endif305306#ifdef HAL_PERIPH_ENABLE_PROXIMITY307AP_Proximity proximity;308#endif309310#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT311void pwm_irq_handler(uint8_t pin, bool pin_state, uint32_t timestamp);312void pwm_hardpoint_init();313void pwm_hardpoint_update();314struct {315uint8_t last_state;316uint32_t last_ts_us;317uint32_t last_send_ms;318uint16_t pwm_value;319uint16_t highest_pwm;320} pwm_hardpoint;321#endif322323#ifdef HAL_PERIPH_ENABLE_HWESC324HWESC_Telem hwesc_telem;325void hwesc_telem_update();326#endif327328#ifdef HAL_PERIPH_ENABLE_EFI329AP_EFI efi;330uint32_t efi_update_ms;331#endif332333#if AP_KDECAN_ENABLED334AP_KDECAN kdecan;335#endif336337#ifdef HAL_PERIPH_ENABLE_ESC_APD338ESC_APD_Telem *apd_esc_telem[APD_ESC_INSTANCES];339void apd_esc_telem_update();340#endif341342#ifdef HAL_PERIPH_ENABLE_RC_OUT343#if HAL_WITH_ESC_TELEM344AP_ESC_Telem esc_telem;345uint8_t get_motor_number(const uint8_t esc_number) const;346uint32_t last_esc_telem_update_ms;347void esc_telem_update();348uint32_t esc_telem_update_period_ms;349#if AP_EXTENDED_ESC_TELEM_ENABLED350void esc_telem_extended_update(const uint32_t &now_ms);351uint32_t last_esc_telem_extended_update;352uint8_t last_esc_telem_extended_sent_id;353#endif354#endif355356SRV_Channels servo_channels;357bool rcout_has_new_data_to_update;358359uint32_t last_esc_raw_command_ms;360uint8_t last_esc_num_channels;361362void rcout_init();363void rcout_init_1Hz();364void rcout_esc(int16_t *rc, uint8_t num_channels);365void rcout_srv_unitless(const uint8_t actuator_id, const float command_value);366void rcout_srv_PWM(const uint8_t actuator_id, const float command_value);367void rcout_update();368void rcout_handle_safety_state(uint8_t safety_state);369#endif370371#ifdef HAL_PERIPH_ENABLE_RCIN372void rcin_init();373void rcin_update();374void can_send_RCInput(uint8_t quality, uint16_t *values, uint8_t nvalues, bool in_failsafe, bool quality_valid);375bool rcin_initialised;376uint32_t rcin_last_sent_RCInput_ms;377const char *rcin_rc_protocol; // protocol currently being decoded378Parameters_RCIN g_rcin;379#endif380381#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE382void batt_balance_update();383BattBalance battery_balance;384#endif385386#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS387SerialOptions serial_options;388#endif389390#if AP_TEMPERATURE_SENSOR_ENABLED391AP_TemperatureSensor temperature_sensor;392#ifdef HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE393void temperature_sensor_update();394uint32_t temperature_last_send_ms;395uint8_t temperature_last_sent_index;396#endif397#endif398399#if defined(HAL_PERIPH_ENABLE_NOTIFY) || defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY)400void update_rainbow();401#endif402#ifdef HAL_PERIPH_ENABLE_NOTIFY403// notification object for LEDs, buzzers etc404AP_Notify notify;405uint64_t vehicle_state = 1; // default to initialisation406float yaw_earth;407uint32_t last_vehicle_state;408409// Handled under LUA script to control LEDs410float get_yaw_earth() { return yaw_earth; }411uint32_t get_vehicle_state() { return vehicle_state; }412#elif defined(AP_SCRIPTING_ENABLED)413// create dummy methods for the case when the user doesn't want to use the notify object414float get_yaw_earth() { return 0.0; }415uint32_t get_vehicle_state() { return 0.0; }416#endif417418#if AP_SCRIPTING_ENABLED419AP_Scripting scripting;420#endif421422#if HAL_LOGGING_ENABLED423static const struct LogStructure log_structure[];424AP_Logger logger;425#endif426427#ifdef HAL_PERIPH_ENABLE_NETWORKING428Networking_Periph networking_periph;429#endif430431#ifdef HAL_PERIPH_ENABLE_RTC432AP_RTC rtc;433#endif434435#if HAL_GCS_ENABLED436GCS_Periph _gcs;437#endif438439#ifdef HAL_PERIPH_ENABLE_RELAY440AP_Relay relay;441#endif442443// setup the var_info table444AP_Param param_loader{var_info};445446static const AP_Param::Info var_info[];447448#ifdef HAL_PERIPH_ENABLE_EFI449uint32_t last_efi_update_ms;450#endif451#ifdef HAL_PERIPH_ENABLE_MAG452uint32_t last_mag_update_ms;453#endif454#ifdef HAL_PERIPH_ENABLE_GPS455uint32_t last_gps_update_ms;456uint32_t last_gps_yaw_ms;457#endif458uint32_t last_relposheading_ms;459#ifdef HAL_PERIPH_ENABLE_BARO460uint32_t last_baro_update_ms;461#endif462#ifdef HAL_PERIPH_ENABLE_AIRSPEED463uint32_t last_airspeed_update_ms;464#endif465#ifdef HAL_PERIPH_ENABLE_GPS466bool saw_gps_lock_once;467#endif468469static AP_Periph_FW *_singleton;470471enum class DebugOptions {472SHOW_STACK = 0,473AUTOREBOOT = 1,474ENABLE_STATS = 2,475};476477// check if an option is set478bool debug_option_is_set(const DebugOptions option) const {479return (uint8_t(g.debug.get()) & (1U<<uint8_t(option))) != 0;480}481482enum class PeriphOptions {483PROBE_CONTINUOUS = 1U<<0,484};485486// check if a periph option is set487bool option_is_set(const PeriphOptions opt) const {488return (uint32_t(g.options.get()) & uint32_t(opt)) != 0;489}490491// show stack as DEBUG msgs492void show_stack_free();493494static bool no_iface_finished_dna;495static constexpr auto can_printf = ::can_printf;496497bool canard_broadcast(uint64_t data_type_signature,498uint16_t data_type_id,499uint8_t priority,500const void* payload,501uint16_t payload_len,502uint8_t iface_mask=0);503504bool canard_respond(CanardInstance* canard_instance,505CanardRxTransfer* transfer,506uint64_t data_type_signature,507uint16_t data_type_id,508const uint8_t *payload,509uint16_t payload_len);510511void onTransferReceived(CanardInstance* canard_instance,512CanardRxTransfer* transfer);513bool shouldAcceptTransfer(const CanardInstance* canard_instance,514uint64_t* out_data_type_signature,515uint16_t data_type_id,516CanardTransferType transfer_type,517uint8_t source_node_id);518519// reboot the peripheral, optionally holding in bootloader520void reboot(bool hold_in_bootloader);521522#if AP_UART_MONITOR_ENABLED523void handle_tunnel_Targetted(CanardInstance* canard_instance, CanardRxTransfer* transfer);524void send_serial_monitor_data();525int8_t get_default_tunnel_serial_port(void) const;526527struct {528ByteBuffer *buffer;529uint32_t last_request_ms;530AP_HAL::UARTDriver *uart;531int8_t uart_num;532uint8_t node_id;533uint8_t protocol;534uint32_t baudrate;535bool locked;536} uart_monitor;537#endif538539// handlers for incoming messages540void handle_get_node_info(CanardInstance* canard_instance, CanardRxTransfer* transfer);541void handle_param_getset(CanardInstance* canard_instance, CanardRxTransfer* transfer);542void handle_param_executeopcode(CanardInstance* canard_instance, CanardRxTransfer* transfer);543void handle_begin_firmware_update(CanardInstance* canard_instance, CanardRxTransfer* transfer);544void handle_allocation_response(CanardInstance* canard_instance, CanardRxTransfer* transfer);545void handle_safety_state(CanardInstance* canard_instance, CanardRxTransfer* transfer);546void handle_arming_status(CanardInstance* canard_instance, CanardRxTransfer* transfer);547void handle_RTCMStream(CanardInstance* canard_instance, CanardRxTransfer* transfer);548void handle_MovingBaselineData(CanardInstance* canard_instance, CanardRxTransfer* transfer);549void handle_esc_rawcommand(CanardInstance* canard_instance, CanardRxTransfer* transfer);550void handle_act_command(CanardInstance* canard_instance, CanardRxTransfer* transfer);551void handle_beep_command(CanardInstance* canard_instance, CanardRxTransfer* transfer);552void handle_lightscommand(CanardInstance* canard_instance, CanardRxTransfer* transfer);553void handle_notify_state(CanardInstance* canard_instance, CanardRxTransfer* transfer);554void handle_hardpoint_command(CanardInstance* canard_instance, CanardRxTransfer* transfer);555556void process1HzTasks(uint64_t timestamp_usec);557void processTx(void);558void processRx(void);559#if HAL_PERIPH_CAN_MIRROR560void processMirror(void);561#endif // HAL_PERIPH_CAN_MIRROR562void cleanup_stale_transactions(uint64_t timestamp_usec);563void update_rx_protocol_stats(int16_t res);564void node_status_send(void);565bool can_do_dna();566uint8_t *get_tid_ptr(uint32_t transfer_desc);567uint16_t pool_peak_percent();568void set_rgb_led(uint8_t red, uint8_t green, uint8_t blue);569570#if AP_SIM_ENABLED571// update simulation of servos572void sim_update_actuator(uint8_t actuator_id);573struct {574uint32_t mask;575uint32_t last_send_ms;576} sim_actuator;577#endif578579struct dronecan_protocol_t {580CanardInstance canard;581uint32_t canard_memory_pool[HAL_CAN_POOL_SIZE/sizeof(uint32_t)];582struct tid_map {583uint32_t transfer_desc;584uint8_t tid;585tid_map *next;586} *tid_map_head;587/*588* Variables used for dynamic node ID allocation.589* RTFM at http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation590*/591uint32_t send_next_node_id_allocation_request_at_ms; ///< When the next node ID allocation request should be sent592uint8_t node_id_allocation_unique_id_offset; ///< Depends on the stage of the next request593uint8_t tx_fail_count;594uint8_t dna_interface = 1;595} dronecan;596597#if AP_SIM_ENABLED598SITL::SIM sitl;599#endif600#if AP_AHRS_ENABLED601AP_AHRS ahrs;602#endif603604uint32_t reboot_request_ms = 0;605606HAL_Semaphore canard_broadcast_semaphore;607};608609#ifndef CAN_APP_NODE_NAME610#define CAN_APP_NODE_NAME "org.ardupilot." CHIBIOS_BOARD_NAME611#endif612613namespace AP614{615AP_Periph_FW& periph();616}617618extern AP_Periph_FW periph;619620621