ardupilot/Tools/AP_Periph/AP_Periph.h

102 lines
2.1 KiB
C
Raw Normal View History

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>
2019-10-03 08:02:56 -03:00
#include <AP_Airspeed/AP_Airspeed.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_Common/AP_FWVersion.h>
2019-10-27 20:46:42 -03:00
#include "version.h"
#include "../AP_Bootloader/app_comms.h"
2019-10-18 21:28:09 -03:00
#if defined(HAL_PERIPH_NEOPIXEL_COUNT) || defined(HAL_PERIPH_ENABLE_NCP5623_LED)
#define AP_PERIPH_HAVE_LED
#endif
2019-05-26 22:46:41 -03:00
#include "Parameters.h"
#include "ch.h"
/*
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();
void can_rangefinder_update();
2019-05-26 22:46:41 -03:00
void load_parameters();
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
#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
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
RangeFinder rangefinder;
#endif
#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;
} pwm_hardpoint;
#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;
2019-05-26 22:46:41 -03:00
};
extern AP_Periph_FW periph;
extern "C" {
void can_printf(const char *fmt, ...);
}