Browse Source

uavcan periph f103-GPS 只保留GPS

periph-1.3.1
NageZeng 3 years ago
parent
commit
76b0ff8bbc
  1. 6
      .vscode/settings.json
  2. 152
      Tools/AP_Periph/AP_Periph.cpp
  3. 22
      Tools/AP_Periph/wscript
  4. 8
      libraries/AP_GPS/AP_GPS.cpp
  5. 2
      libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef-bl.dat
  6. 8
      libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat
  7. 2
      libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.inc
  8. 12
      libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc

6
.vscode/settings.json vendored

@ -1,4 +1,8 @@ @@ -1,4 +1,8 @@
{
"cSpell.language": "en-GB",
"astyle.astylerc": "${workspaceFolder}/Tools/CodeStyle/astylerc"
"astyle.astylerc": "${workspaceFolder}/Tools/CodeStyle/astylerc",
"files.associations": {
"*.ipp": "cpp",
"*.tcc": "cpp"
}
}

152
Tools/AP_Periph/AP_Periph.cpp

@ -30,7 +30,9 @@ @@ -30,7 +30,9 @@
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
#include <AP_HAL_ChibiOS/I2CDevice.h>
#endif
#ifndef HAL_PERIPH_ENABLE_GPS
#define HAL_PERIPH_ENABLE_GPS 1
#endif
extern const AP_HAL::HAL &hal;
AP_Periph_FW periph;
@ -97,6 +99,8 @@ void AP_Periph_FW::init() @@ -97,6 +99,8 @@ void AP_Periph_FW::init()
#if !HAL_GCS_ENABLED
hal.serial(0)->begin(AP_SERIALMANAGER_CONSOLE_BAUD, 32, 32);
#endif
hal.serial(1)->begin(115200, 128, 128);
hal.serial(3)->begin(115200, 128, 256);
load_parameters();
@ -153,66 +157,6 @@ void AP_Periph_FW::init() @@ -153,66 +157,6 @@ void AP_Periph_FW::init()
}
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
compass.init();
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
baro.init();
#endif
#ifdef HAL_PERIPH_ENABLE_BATTERY
battery.lib.init();
#endif
#if defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_RC_OUT)
hal.rcout->init();
#endif
#ifdef HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY
hal.rcout->set_serial_led_num_LEDs(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY, AP_HAL::RCOutput::MODE_NEOPIXEL);
#endif
#ifdef HAL_PERIPH_ENABLE_RC_OUT
rcout_init();
#endif
#ifdef HAL_PERIPH_ENABLE_ADSB
adsb_init();
#endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
if (airspeed.enabled()){
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
const bool pins_enabled = ChibiOS::I2CBus::check_select_pins(0x01);
if (pins_enabled) {
ChibiOS::I2CBus::set_bus_to_floating(0);
#ifdef HAL_GPIO_PIN_LED_CAN_I2C
palWriteLine(HAL_GPIO_PIN_LED_CAN_I2C, 1);
#endif
} else {
// Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit(); here
airspeed.init();
}
#else
// Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit(); here
airspeed.init();
#endif
}
#endif
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
if (rangefinder.get_type(0) != RangeFinder::Type::NONE && g.rangefinder_port >= 0) {
auto *uart = hal.serial(g.rangefinder_port);
if (uart != nullptr) {
uart->begin(g.rangefinder_baud);
serial_manager.set_protocol_and_baud(g.rangefinder_port, AP_SerialManager::SerialProtocol_Rangefinder, g.rangefinder_baud);
rangefinder.init(ROTATION_NONE);
}
}
#endif
#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT
pwm_hardpoint_init();
#endif
@ -237,74 +181,6 @@ void AP_Periph_FW::init() @@ -237,74 +181,6 @@ void AP_Periph_FW::init()
start_ms = AP_HAL::native_millis();
}
#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY)
/*
rotating rainbow pattern on startup
*/
void AP_Periph_FW::update_rainbow()
{
#ifdef HAL_PERIPH_ENABLE_NOTIFY
if (notify.get_led_len() != 8) {
return;
}
#endif
static bool rainbow_done;
if (rainbow_done) {
return;
}
uint32_t now = AP_HAL::native_millis();
if (now - start_ms > 1500) {
rainbow_done = true;
#if defined (HAL_PERIPH_ENABLE_NOTIFY)
periph.notify.handle_rgb(0, 0, 0);
#elif defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, -1, 0, 0, 0);
hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);
#endif
return;
}
static uint32_t last_update_ms;
const uint8_t step_ms = 30;
if (now - last_update_ms < step_ms) {
return;
}
const struct {
uint8_t red;
uint8_t green;
uint8_t blue;
} rgb_rainbow[] = {
{ 255, 0, 0 },
{ 255, 127, 0 },
{ 255, 255, 0 },
{ 0, 255, 0 },
{ 0, 0, 255 },
{ 75, 0, 130 },
{ 143, 0, 255 },
{ 0, 0, 0 },
};
last_update_ms = now;
static uint8_t step;
const uint8_t nsteps = ARRAY_SIZE(rgb_rainbow);
float brightness = 0.3;
for (uint8_t n=0; n<8; n++) {
uint8_t i = (step + n) % nsteps;
#if defined (HAL_PERIPH_ENABLE_NOTIFY)
periph.notify.handle_rgb(
#elif defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, n,
#endif
rgb_rainbow[i].red*brightness,
rgb_rainbow[i].green*brightness,
rgb_rainbow[i].blue*brightness);
}
step++;
#if defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)
hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);
#endif
}
#endif // HAL_PERIPH_ENABLE_NOTIFY
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && CH_DBG_ENABLE_STACK_CHECK == TRUE
void AP_Periph_FW::show_stack_free()
@ -333,26 +209,18 @@ void AP_Periph_FW::update() @@ -333,26 +209,18 @@ void AP_Periph_FW::update()
{
static uint32_t last_led_ms;
uint32_t now = AP_HAL::native_millis();
if (now - last_led_ms > 1000) {
if (now - last_led_ms > 500) {
last_led_ms = now;
hal.serial(1)->printf("update: %lu\n", now);
#ifdef HAL_GPIO_PIN_LED
if (!no_iface_finished_dna) {
palToggleLine(HAL_GPIO_PIN_LED);
}
#endif
#if 0
#if 1
#ifdef HAL_PERIPH_ENABLE_GPS
hal.serial(0)->printf("GPS status: %u\n", (unsigned)gps.status());
#endif
#ifdef HAL_PERIPH_ENABLE_MAG
const Vector3f &field = compass.get_field();
hal.serial(0)->printf("MAG (%d,%d,%d)\n", int(field.x), int(field.y), int(field.z));
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
hal.serial(0)->printf("BARO H=%u P=%.2f T=%.2f\n", baro.healthy(), baro.get_pressure(), baro.get_temperature());
#endif
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
hal.serial(0)->printf("RNG %u %ucm\n", rangefinder.num_sensors(), rangefinder.distance_cm_orient(ROTATION_NONE));
hal.serial(1)->printf("GPS status: %u\n", (unsigned)gps.status());
#endif
hal.scheduler->delay(1);
#endif

22
Tools/AP_Periph/wscript

@ -35,7 +35,7 @@ def build(bld): @@ -35,7 +35,7 @@ def build(bld):
'AP_HAL_Empty',
'AP_Math',
'AP_BoardConfig',
'AP_BattMonitor',
# 'AP_BattMonitor',
'AP_CANManager',
'AP_Param',
'StorageManager',
@ -44,24 +44,24 @@ def build(bld): @@ -44,24 +44,24 @@ def build(bld):
'AP_GPS',
'AP_SerialManager',
'AP_RTC',
'AP_Compass',
'AP_Baro',
# 'AP_Compass',
# 'AP_Baro',
'Filter',
'AP_InternalError',
'AP_Airspeed',
'AP_RangeFinder',
# 'AP_Airspeed',
# 'AP_RangeFinder',
'AP_ROMFS',
'AP_MSP',
'SRV_Channel',
# 'SRV_Channel',
'AP_Notify',
'AP_SerialLED',
'AP_Filesystem',
'AP_InertialSensor',
'AP_AccelCal',
# 'AP_InertialSensor',
# 'AP_AccelCal',
'AP_Logger',
'AC_PID',
'AP_BLHeli',
'AP_ESC_Telem',
# 'AC_PID',
# 'AP_BLHeli',
# 'AP_ESC_Telem',
]
bld.ap_stlib(
name= 'AP_Periph_libs',

8
libraries/AP_GPS/AP_GPS.cpp

@ -734,19 +734,19 @@ void AP_GPS::detect_instance(uint8_t instance) @@ -734,19 +734,19 @@ void AP_GPS::detect_instance(uint8_t instance)
}
#ifndef HAL_BUILD_AP_PERIPH
#if AP_GPS_SBP2_ENABLED
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
else if (( _type[instance] == GPS_TYPE_SBP) &&
AP_GPS_SBP2::_detect(dstate->sbp2_detect_state, data)) {
new_gps = new AP_GPS_SBP2(*this, state[instance], _port[instance]);
}
#endif //AP_GPS_SBP2_ENABLED
#if AP_GPS_SBP_ENABLED
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
else if (( _type[instance] == GPS_TYPE_SBP) &&
AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) {
new_gps = new AP_GPS_SBP(*this, state[instance], _port[instance]);
}
#endif //AP_GPS_SBP_ENABLED
#if !HAL_MINIMIZE_FEATURES && AP_GPS_SIRF_ENABLED
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SIRF) &&
else if (( _type[instance] == GPS_TYPE_SIRF) &&
AP_GPS_SIRF::_detect(dstate->sirf_detect_state, data)) {
new_gps = new AP_GPS_SIRF(*this, state[instance], _port[instance]);
}
@ -758,7 +758,7 @@ void AP_GPS::detect_instance(uint8_t instance) @@ -758,7 +758,7 @@ void AP_GPS::detect_instance(uint8_t instance)
}
#endif // AP_GPS_ERB_ENABLED
#if AP_GPS_NMEA_ENABLED
else if ((_type[instance] == GPS_TYPE_NMEA ||
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_NMEA ||
_type[instance] == GPS_TYPE_HEMI ||
_type[instance] == GPS_TYPE_ALLYSTAR) &&
AP_GPS_NMEA::_detect(dstate->nmea_detect_state, data)) {

2
libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef-bl.dat

@ -1,4 +1,4 @@ @@ -1,4 +1,4 @@
include ../f103-periph/hwdef-bl.inc
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps"
define CAN_APP_NODE_NAME "org.zrzk.ap_periph_gps_bl"

8
libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat

@ -1,10 +1,10 @@ @@ -1,10 +1,10 @@
include ../f103-periph/hwdef.inc
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps"
define CAN_APP_NODE_NAME "org.zrzk.ap_periph_gps"
# and support all external compass types
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
#define HAL_PROBE_EXTERNAL_I2C_COMPASSES
# increase TX size for RTCM
undef HAL_UART_MIN_TX_SIZE
@ -12,6 +12,6 @@ define HAL_UART_MIN_TX_SIZE 256 @@ -12,6 +12,6 @@ define HAL_UART_MIN_TX_SIZE 256
# GPS+MAG
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_MAG
#define HAL_PERIPH_ENABLE_MAG
#define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY
define HAL_PERIPH_ENABLE_TOSHIBA_LED_WITHOUT_NOTIFY
#define HAL_PERIPH_ENABLE_TOSHIBA_LED_WITHOUT_NOTIFY

2
libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.inc

@ -31,7 +31,7 @@ STDOUT_BAUDRATE 57600 @@ -31,7 +31,7 @@ STDOUT_BAUDRATE 57600
SERIAL_ORDER
define HAL_USE_UART FALSE
PA4 LED_BOOTLOADER OUTPUT LOW
PC11 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 1
# USART1

12
libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc

@ -28,18 +28,18 @@ FLASH_SIZE_KB 128 @@ -28,18 +28,18 @@ FLASH_SIZE_KB 128
# order of UARTs
SERIAL_ORDER EMPTY EMPTY EMPTY USART1
SERIAL_ORDER EMPTY USART2 EMPTY USART1
# a LED to flash
PA4 LED OUTPUT LOW
PC11 LED OUTPUT LOW
# USART1, connected to GPS
PA9 USART1_TX USART1 SPEED_HIGH NODMA
PA10 USART1_RX USART1 SPEED_HIGH NODMA
# USART2 for debug (disabled)
# PA2 USART2_TX USART2 SPEED_HIGH NODMA
# PA3 USART2_RX USART2 SPEED_HIGH NODMA
# USART2 for debug (enable)
PA2 USART2_TX USART2 SPEED_HIGH NODMA
PA3 USART2_RX USART2 SPEED_HIGH NODMA
define HAL_UART_NODMA
@ -134,3 +134,5 @@ define HAL_CAN_RX_QUEUE_SIZE 32 @@ -134,3 +134,5 @@ define HAL_CAN_RX_QUEUE_SIZE 32
# disable stack checking to reduce flash cost
define CH_DBG_ENABLE_STACK_CHECK FALSE
define HAL_GCS_ENABLED 0
Loading…
Cancel
Save