2019-05-26 22:46:41 -03:00
|
|
|
#include "AP_Periph.h"
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL &hal;
|
|
|
|
|
2020-12-26 15:18:08 -04:00
|
|
|
#ifndef HAL_PERIPH_LED_BRIGHT_DEFAULT
|
|
|
|
#define HAL_PERIPH_LED_BRIGHT_DEFAULT 100
|
2019-10-18 21:28:09 -03:00
|
|
|
#endif
|
|
|
|
|
2020-12-26 15:18:08 -04:00
|
|
|
#ifndef HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT
|
|
|
|
#define HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT 115200
|
2020-12-22 19:29:59 -04:00
|
|
|
#endif
|
|
|
|
|
2020-12-26 15:18:08 -04:00
|
|
|
#ifndef HAL_PERIPH_RANGEFINDER_PORT_DEFAULT
|
|
|
|
#define HAL_PERIPH_RANGEFINDER_PORT_DEFAULT 3
|
2020-12-22 19:29:59 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef HAL_PERIPH_GPS_PORT_DEFAULT
|
|
|
|
#define HAL_PERIPH_GPS_PORT_DEFAULT 3
|
|
|
|
#endif
|
|
|
|
|
2020-01-24 19:59:01 -04:00
|
|
|
#ifndef HAL_PERIPH_ADSB_BAUD_DEFAULT
|
|
|
|
#define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600
|
|
|
|
#endif
|
2020-12-17 22:12:25 -04:00
|
|
|
#ifndef HAL_PERIPH_ADSB_PORT_DEFAULT
|
|
|
|
#define HAL_PERIPH_ADSB_PORT_DEFAULT 1
|
|
|
|
#endif
|
2020-01-24 19:59:01 -04:00
|
|
|
|
2020-12-26 19:35:15 -04:00
|
|
|
#ifndef AP_PERIPH_MSP_PORT_DEFAULT
|
|
|
|
#define AP_PERIPH_MSP_PORT_DEFAULT 1
|
|
|
|
#endif
|
|
|
|
|
2019-05-26 22:46:41 -03:00
|
|
|
/*
|
|
|
|
* AP_Periph parameter definitions
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
|
|
|
|
#define GSCALAR(v, name, def) { periph.g.v.vtype, name, Parameters::k_param_ ## v, &periph.g.v, {def_value : def} }
|
|
|
|
#define ASCALAR(v, name, def) { periph.aparm.v.vtype, name, Parameters::k_param_ ## v, (const void *)&periph.aparm.v, {def_value : def} }
|
|
|
|
#define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &periph.g.v, {group_info : class::var_info} }
|
|
|
|
#define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&periph.v, {group_info : class::var_info} }
|
|
|
|
#define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&periph.v, {group_info : class::var_info} }
|
|
|
|
|
|
|
|
const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|
|
|
// @Param: FORMAT_VERSION
|
|
|
|
// @DisplayName: Eeprom format version number
|
|
|
|
// @Description: This value is incremented when changes are made to the eeprom format
|
|
|
|
// @User: Advanced
|
|
|
|
GSCALAR(format_version, "FORMAT_VERSION", 0),
|
|
|
|
|
|
|
|
// can node number, 0 for dynamic node allocation
|
|
|
|
GSCALAR(can_node, "CAN_NODE", HAL_CAN_DEFAULT_NODE_ID),
|
|
|
|
|
|
|
|
// can node baudrate
|
|
|
|
GSCALAR(can_baudrate, "CAN_BAUDRATE", 1000000),
|
2019-10-23 04:57:27 -03:00
|
|
|
|
|
|
|
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
|
|
|
|
// trigger bootloader flash
|
|
|
|
GSCALAR(flash_bootloader, "FLASH_BOOTLOADER", 0),
|
|
|
|
#endif
|
2020-11-29 19:14:56 -04:00
|
|
|
|
|
|
|
GSCALAR(debug, "DEBUG", 0),
|
|
|
|
|
2020-12-17 01:46:31 -04:00
|
|
|
GSCALAR(serial_number, "BRD_SERIAL_NUM", 0),
|
|
|
|
|
2020-12-29 01:06:44 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY
|
2019-08-31 04:20:53 -03:00
|
|
|
GSCALAR(buzz_volume, "BUZZER_VOLUME", 100),
|
|
|
|
#endif
|
|
|
|
|
2019-05-26 22:46:41 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_GPS
|
|
|
|
// GPS driver
|
2020-12-30 11:02:31 -04:00
|
|
|
// @Group: GPS
|
2019-10-19 01:36:14 -03:00
|
|
|
// @Path: ../../libraries/AP_GPS/AP_GPS.cpp
|
2020-12-30 11:02:31 -04:00
|
|
|
GOBJECT(gps, "GPS", AP_GPS),
|
2020-12-22 19:29:59 -04:00
|
|
|
|
|
|
|
// @Param: GPS_PORT
|
|
|
|
// @DisplayName: GPS Serial Port
|
|
|
|
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to GPS.
|
|
|
|
// @Range: 0 10
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
|
|
|
// @RebootRequired: True
|
|
|
|
GSCALAR(gps_port, "GPS_PORT", HAL_PERIPH_GPS_PORT_DEFAULT),
|
2019-05-26 22:46:41 -03:00
|
|
|
#endif
|
|
|
|
|
2020-11-21 01:29:10 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_BATTERY
|
|
|
|
// @Group: BATT
|
|
|
|
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
|
|
|
|
GOBJECT(battery, "BATT", AP_BattMonitor),
|
|
|
|
#endif
|
|
|
|
|
2019-05-26 22:46:41 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_MAG
|
|
|
|
// @Group: COMPASS_
|
2019-10-19 01:36:14 -03:00
|
|
|
// @Path: ../../libraries/AP_Compass/AP_Compass.cpp
|
2019-05-26 22:46:41 -03:00
|
|
|
GOBJECT(compass, "COMPASS_", Compass),
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_BARO
|
|
|
|
// Baro driver
|
2020-12-03 04:13:33 -04:00
|
|
|
// @Group: BARO
|
2019-10-19 01:36:14 -03:00
|
|
|
// @Path: ../../libraries/AP_Baro/AP_Baro.cpp
|
2020-12-03 04:13:33 -04:00
|
|
|
GOBJECT(baro, "BARO", AP_Baro),
|
2019-12-25 04:58:51 -04:00
|
|
|
GSCALAR(baro_enable, "BARO_ENABLE", 1),
|
2019-05-26 22:46:41 -03:00
|
|
|
#endif
|
2019-08-31 04:20:53 -03:00
|
|
|
|
2020-12-29 01:06:44 -04:00
|
|
|
#ifdef AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
|
2020-12-26 15:18:08 -04:00
|
|
|
GSCALAR(led_brightness, "LED_BRIGHTNESS", HAL_PERIPH_LED_BRIGHT_DEFAULT),
|
2019-10-10 00:18:59 -03:00
|
|
|
#endif
|
|
|
|
|
2019-10-03 08:02:56 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
|
|
|
// Airspeed driver
|
|
|
|
// @Group: ARSP
|
2019-10-19 01:36:14 -03:00
|
|
|
// @Path: ../../libraries/AP_Airspeed/AP_Airspeed.cpp
|
2019-10-03 08:02:56 -03:00
|
|
|
GOBJECT(airspeed, "ARSP", AP_Airspeed),
|
|
|
|
#endif
|
2019-10-19 01:36:14 -03:00
|
|
|
|
2019-10-27 21:31:29 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
|
2020-12-26 15:18:08 -04:00
|
|
|
GSCALAR(rangefinder_baud, "RNGFND_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),
|
|
|
|
GSCALAR(rangefinder_port, "RNGFND_PORT", HAL_PERIPH_RANGEFINDER_PORT_DEFAULT),
|
2019-10-27 21:31:29 -03:00
|
|
|
|
2019-10-19 01:36:14 -03:00
|
|
|
// Rangefinder driver
|
|
|
|
// @Group: RNGFND
|
|
|
|
// @Path: ../../libraries/AP_RangeFinder/Rangefinder.cpp
|
|
|
|
GOBJECT(rangefinder, "RNGFND", RangeFinder),
|
|
|
|
#endif
|
2019-11-26 20:06:34 -04:00
|
|
|
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_ADSB
|
2020-01-24 19:59:01 -04:00
|
|
|
GSCALAR(adsb_baudrate, "ADSB_BAUDRATE", HAL_PERIPH_ADSB_BAUD_DEFAULT),
|
2020-12-17 22:12:25 -04:00
|
|
|
GSCALAR(adsb_port, "ADSB_PORT", HAL_PERIPH_ADSB_PORT_DEFAULT),
|
2019-11-26 20:06:34 -04:00
|
|
|
#endif
|
2019-12-19 02:21:25 -04:00
|
|
|
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT
|
|
|
|
GSCALAR(hardpoint_id, "HARDPOINT_ID", HAL_PWM_HARDPOINT_ID_DEFAULT),
|
2019-12-19 03:46:03 -04:00
|
|
|
GSCALAR(hardpoint_rate, "HARDPOINT_RATE", 100),
|
2019-12-19 02:21:25 -04:00
|
|
|
#endif
|
2020-02-14 01:18:20 -04:00
|
|
|
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_HWESC
|
|
|
|
GSCALAR(esc_number, "ESC_NUMBER", 0),
|
|
|
|
#endif
|
2020-11-29 19:14:56 -04:00
|
|
|
|
2020-12-12 05:08:45 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_RC_OUT
|
|
|
|
// Servo driver
|
|
|
|
// @Group: OUT
|
|
|
|
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
|
|
|
|
GOBJECT(servo_channels, "OUT", SRV_Channels),
|
2021-03-13 18:56:43 -04:00
|
|
|
|
|
|
|
// PWM type for ESCs (to allow for DShot and OneShot)
|
|
|
|
GSCALAR(esc_pwm_type, "ESC_PWM_TYPE", 0),
|
2020-12-12 05:08:45 -04:00
|
|
|
#endif
|
|
|
|
|
2020-12-26 19:35:15 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_MSP
|
|
|
|
GSCALAR(msp_port, "MSP_PORT", AP_PERIPH_MSP_PORT_DEFAULT),
|
|
|
|
#endif
|
|
|
|
|
2020-12-29 01:06:44 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
|
|
|
// @Group: NTF_
|
|
|
|
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
|
|
|
|
GOBJECT(notify, "NTF_", AP_Notify),
|
|
|
|
#endif
|
|
|
|
|
2019-05-26 22:46:41 -03:00
|
|
|
AP_VAREND
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
void AP_Periph_FW::load_parameters(void)
|
|
|
|
{
|
|
|
|
AP_Param::setup_sketch_defaults();
|
|
|
|
|
|
|
|
if (!AP_Param::check_var_info()) {
|
|
|
|
hal.console->printf("Bad parameter table\n");
|
|
|
|
AP_HAL::panic("Bad parameter table");
|
|
|
|
}
|
|
|
|
if (!g.format_version.load() ||
|
|
|
|
g.format_version != Parameters::k_format_version) {
|
|
|
|
// erase all parameters
|
|
|
|
StorageManager::erase();
|
|
|
|
AP_Param::erase_all();
|
|
|
|
|
|
|
|
// save the current format version
|
|
|
|
g.format_version.set_and_save(Parameters::k_format_version);
|
|
|
|
}
|
|
|
|
|
|
|
|
// Load all auto-loaded EEPROM variables
|
|
|
|
AP_Param::load_all();
|
|
|
|
}
|