mirror of https://github.com/ArduPilot/ardupilot
AP_BoardConfig: called board_setup() even without autodetect
we need to init hal.rcou and hal.gpio
This commit is contained in:
parent
b48b436923
commit
82cc36d6d0
|
@ -179,9 +179,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
|
|||
|
||||
void AP_BoardConfig::init()
|
||||
{
|
||||
#if AP_FEATURE_BOARD_DETECT
|
||||
board_setup();
|
||||
#endif
|
||||
|
||||
#if HAL_HAVE_IMU_HEATER
|
||||
// let the HAL know the target temperature. We pass a pointer as
|
||||
|
|
|
@ -141,12 +141,9 @@ private:
|
|||
void px4_setup_peripherals(void);
|
||||
#endif
|
||||
|
||||
void board_setup(void);
|
||||
|
||||
void board_init_safety(void);
|
||||
void board_setup_safety_mask(void);
|
||||
void board_setup_uart(void);
|
||||
void board_setup_sbus(void);
|
||||
void board_setup_drivers(void);
|
||||
bool spi_check_register(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag = 0x80);
|
||||
void validate_board_type(void);
|
||||
|
@ -154,6 +151,10 @@ private:
|
|||
|
||||
#endif // AP_FEATURE_BOARD_DETECT
|
||||
|
||||
void board_setup_uart(void);
|
||||
void board_setup_sbus(void);
|
||||
void board_setup(void);
|
||||
|
||||
static bool _in_sensor_config_error;
|
||||
|
||||
// target temperarure for IMU in Celsius, or -1 to disable
|
||||
|
|
|
@ -20,24 +20,11 @@
|
|||
#include "AP_BoardConfig.h"
|
||||
#include <stdio.h>
|
||||
|
||||
#if AP_FEATURE_BOARD_DETECT
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
AP_BoardConfig::px4_board_type AP_BoardConfig::px4_configured_board;
|
||||
#if AP_FEATURE_BOARD_DETECT
|
||||
|
||||
/*
|
||||
setup flow control on UARTs
|
||||
*/
|
||||
void AP_BoardConfig::board_setup_uart()
|
||||
{
|
||||
#if AP_FEATURE_RTSCTS
|
||||
hal.uartC->set_flow_control((AP_HAL::UARTDriver::flow_control)state.ser1_rtscts.get());
|
||||
if (hal.uartD != nullptr) {
|
||||
hal.uartD->set_flow_control((AP_HAL::UARTDriver::flow_control)state.ser2_rtscts.get());
|
||||
}
|
||||
#endif
|
||||
}
|
||||
AP_BoardConfig::px4_board_type AP_BoardConfig::px4_configured_board;
|
||||
|
||||
/*
|
||||
init safety state
|
||||
|
@ -57,38 +44,6 @@ void AP_BoardConfig::board_init_safety()
|
|||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
setup SBUS
|
||||
*/
|
||||
void AP_BoardConfig::board_setup_sbus(void)
|
||||
{
|
||||
#if AP_FEATURE_SBUS_OUT
|
||||
if (state.sbus_out_rate.get() >= 1) {
|
||||
static const struct {
|
||||
uint8_t value;
|
||||
uint16_t rate;
|
||||
} rates[] = {
|
||||
{ 1, 50 },
|
||||
{ 2, 75 },
|
||||
{ 3, 100 },
|
||||
{ 4, 150 },
|
||||
{ 5, 200 },
|
||||
{ 6, 250 },
|
||||
{ 7, 300 }
|
||||
};
|
||||
uint16_t rate = 300;
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(rates); i++) {
|
||||
if (rates[i].value == state.sbus_out_rate) {
|
||||
rate = rates[i].rate;
|
||||
}
|
||||
}
|
||||
if (!hal.rcout->enable_px4io_sbus_out(rate)) {
|
||||
hal.console->printf("Failed to enable SBUS out\n");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
|
||||
extern "C" {
|
||||
int fmu_main(int, char **);
|
||||
|
@ -269,6 +224,54 @@ void AP_BoardConfig::board_autodetect(void)
|
|||
|
||||
}
|
||||
|
||||
#endif // AP_FEATURE_BOARD_DETECT
|
||||
|
||||
/*
|
||||
setup flow control on UARTs
|
||||
*/
|
||||
void AP_BoardConfig::board_setup_uart()
|
||||
{
|
||||
#if AP_FEATURE_RTSCTS
|
||||
hal.uartC->set_flow_control((AP_HAL::UARTDriver::flow_control)state.ser1_rtscts.get());
|
||||
if (hal.uartD != nullptr) {
|
||||
hal.uartD->set_flow_control((AP_HAL::UARTDriver::flow_control)state.ser2_rtscts.get());
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
setup SBUS
|
||||
*/
|
||||
void AP_BoardConfig::board_setup_sbus(void)
|
||||
{
|
||||
#if AP_FEATURE_SBUS_OUT
|
||||
if (state.sbus_out_rate.get() >= 1) {
|
||||
static const struct {
|
||||
uint8_t value;
|
||||
uint16_t rate;
|
||||
} rates[] = {
|
||||
{ 1, 50 },
|
||||
{ 2, 75 },
|
||||
{ 3, 100 },
|
||||
{ 4, 150 },
|
||||
{ 5, 200 },
|
||||
{ 6, 250 },
|
||||
{ 7, 300 }
|
||||
};
|
||||
uint16_t rate = 300;
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(rates); i++) {
|
||||
if (rates[i].value == state.sbus_out_rate) {
|
||||
rate = rates[i].rate;
|
||||
}
|
||||
}
|
||||
if (!hal.rcout->enable_px4io_sbus_out(rate)) {
|
||||
hal.console->printf("Failed to enable SBUS out\n");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
setup peripherals and drivers
|
||||
*/
|
||||
|
@ -286,7 +289,8 @@ void AP_BoardConfig::board_setup()
|
|||
#endif
|
||||
board_setup_uart();
|
||||
board_setup_sbus();
|
||||
#if AP_FEATURE_BOARD_DETECT
|
||||
board_setup_drivers();
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // HAL_BOARD_PX4
|
||||
|
|
Loading…
Reference in New Issue