mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_BoardConfig: fixup for merge after VRBrain changes
This commit is contained in:
parent
77bee322e9
commit
0d59935847
@ -59,6 +59,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
|
|||||||
// @Values: 0:No PWMs,2:Two PWMs,4:Four PWMs,6:Six PWMs,7:Three PWMs and One Capture
|
// @Values: 0:No PWMs,2:Two PWMs,4:Four PWMs,6:Six PWMs,7:Three PWMs and One Capture
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("PWM_COUNT", 0, AP_BoardConfig, px4.pwm_count, BOARD_PWM_COUNT_DEFAULT),
|
AP_GROUPINFO("PWM_COUNT", 0, AP_BoardConfig, px4.pwm_count, BOARD_PWM_COUNT_DEFAULT),
|
||||||
|
#endif
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
// @Param: SER1_RTSCTS
|
// @Param: SER1_RTSCTS
|
||||||
@ -74,14 +75,16 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
|
|||||||
// @Values: 0:Disabled,1:Enabled,2:Auto
|
// @Values: 0:Disabled,1:Enabled,2:Auto
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("SER2_RTSCTS", 2, AP_BoardConfig, px4.ser2_rtscts, 2),
|
AP_GROUPINFO("SER2_RTSCTS", 2, AP_BoardConfig, px4.ser2_rtscts, 2),
|
||||||
|
#endif
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
// @Param: SAFETYENABLE
|
// @Param: SAFETYENABLE
|
||||||
// @DisplayName: Enable use of safety arming switch
|
// @DisplayName: Enable use of safety arming switch
|
||||||
// @Description: This controls the default state of the safety switch at startup. When set to 1 the safety switch will start in the safe state (flashing) at boot. When set to zero the safety switch will start in the unsafe state (solid) at startup. Note that if a safety switch is fitted the user can still control the safety state after startup using the switch. The safety state can also be controlled in software using a MAVLink message.
|
// @Description: This controls the default state of the safety switch at startup. When set to 1 the safety switch will start in the safe state (flashing) at boot. When set to zero the safety switch will start in the unsafe state (solid) at startup. Note that if a safety switch is fitted the user can still control the safety state after startup using the switch. The safety state can also be controlled in software using a MAVLink message.
|
||||||
// @Values: 0:Disabled,1:Enabled
|
// @Values: 0:Disabled,1:Enabled
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("SAFETYENABLE", 3, AP_BoardConfig, px4.safety_enable, 1),
|
AP_GROUPINFO("SAFETYENABLE", 3, AP_BoardConfig, px4.safety_enable, BOARD_SAFETY_ENABLE_DEFAULT),
|
||||||
|
#endif
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
// @Param: SBUS_OUT
|
// @Param: SBUS_OUT
|
||||||
@ -138,18 +141,16 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
|
|||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 && !defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
|
||||||
extern "C" int uavcan_main(int argc, const char *argv[]);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
void AP_BoardConfig::init()
|
void AP_BoardConfig::init()
|
||||||
{
|
{
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
px4_setup();
|
px4_setup();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAL_HAVE_IMU_HEATER
|
||||||
// let the HAL know the target temperature. We pass a pointer as
|
// let the HAL know the target temperature. We pass a pointer as
|
||||||
// we want the user to be able to change the parameter without
|
// we want the user to be able to change the parameter without
|
||||||
// rebooting
|
// rebooting
|
||||||
hal.util->set_imu_target_temp((int8_t *)&_imu_target_temperature);
|
hal.util->set_imu_target_temp((int8_t *)&_imu_target_temperature);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -21,7 +21,7 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include "AP_BoardConfig.h"
|
#include "AP_BoardConfig.h"
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <sys/types.h>
|
#include <sys/types.h>
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
@ -32,17 +32,6 @@
|
|||||||
#include <nuttx/arch.h>
|
#include <nuttx/arch.h>
|
||||||
#include <spawn.h>
|
#include <spawn.h>
|
||||||
|
|
||||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
|
||||||
#define BOARD_PWM_COUNT_DEFAULT 2
|
|
||||||
#define BOARD_SER1_RTSCTS_DEFAULT 0 // no flow control on UART5 on FMUv1
|
|
||||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
|
|
||||||
#define BOARD_PWM_COUNT_DEFAULT 6
|
|
||||||
#define BOARD_SER1_RTSCTS_DEFAULT 2
|
|
||||||
#else // V2
|
|
||||||
#define BOARD_PWM_COUNT_DEFAULT 4
|
|
||||||
#define BOARD_SER1_RTSCTS_DEFAULT 2
|
|
||||||
#endif
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -65,7 +54,10 @@ extern "C" {
|
|||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 && !defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||||
|
/*
|
||||||
|
this is needed for the code to wait for CAN startup
|
||||||
|
*/
|
||||||
#define _UAVCAN_IOCBASE (0x4000) // IOCTL base for module UAVCAN
|
#define _UAVCAN_IOCBASE (0x4000) // IOCTL base for module UAVCAN
|
||||||
#define _UAVCAN_IOC(_n) (_IOC(_UAVCAN_IOCBASE, _n))
|
#define _UAVCAN_IOC(_n) (_IOC(_UAVCAN_IOCBASE, _n))
|
||||||
|
|
||||||
@ -112,11 +104,13 @@ void AP_BoardConfig::px4_setup_pwm()
|
|||||||
hal.console->printf("RCOutput: unable to setup AUX PWM with BRD_PWM_COUNT %u\n", mode_parm);
|
hal.console->printf("RCOutput: unable to setup AUX PWM with BRD_PWM_COUNT %u\n", mode_parm);
|
||||||
}
|
}
|
||||||
close(fd);
|
close(fd);
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
if (mode_table[i].num_gpios < 2) {
|
if (mode_table[i].num_gpios < 2) {
|
||||||
// reduce change of config mistake where relay and PWM interfere
|
// reduce change of config mistake where relay and PWM interfere
|
||||||
AP_Param::set_default_by_name("RELAY_PIN", -1);
|
AP_Param::set_default_by_name("RELAY_PIN", -1);
|
||||||
AP_Param::set_default_by_name("RELAY_PIN2", -1);
|
AP_Param::set_default_by_name("RELAY_PIN2", -1);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -126,10 +120,12 @@ void AP_BoardConfig::px4_setup_pwm()
|
|||||||
*/
|
*/
|
||||||
void AP_BoardConfig::px4_setup_uart()
|
void AP_BoardConfig::px4_setup_uart()
|
||||||
{
|
{
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
hal.uartC->set_flow_control((AP_HAL::UARTDriver::flow_control)px4.ser1_rtscts.get());
|
hal.uartC->set_flow_control((AP_HAL::UARTDriver::flow_control)px4.ser1_rtscts.get());
|
||||||
if (hal.uartD != NULL) {
|
if (hal.uartD != NULL) {
|
||||||
hal.uartD->set_flow_control((AP_HAL::UARTDriver::flow_control)px4.ser2_rtscts.get());
|
hal.uartD->set_flow_control((AP_HAL::UARTDriver::flow_control)px4.ser2_rtscts.get());
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -137,6 +133,7 @@ void AP_BoardConfig::px4_setup_uart()
|
|||||||
*/
|
*/
|
||||||
void AP_BoardConfig::px4_setup_safety()
|
void AP_BoardConfig::px4_setup_safety()
|
||||||
{
|
{
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
// setup channels to ignore the armed state
|
// setup channels to ignore the armed state
|
||||||
int px4io_fd = open("/dev/px4io", 0);
|
int px4io_fd = open("/dev/px4io", 0);
|
||||||
if (px4io_fd != -1) {
|
if (px4io_fd != -1) {
|
||||||
@ -145,6 +142,7 @@ void AP_BoardConfig::px4_setup_safety()
|
|||||||
}
|
}
|
||||||
close(px4io_fd);
|
close(px4io_fd);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if (px4.safety_enable.get() == 0) {
|
if (px4.safety_enable.get() == 0) {
|
||||||
hal.rcout->force_safety_off();
|
hal.rcout->force_safety_off();
|
||||||
@ -157,6 +155,7 @@ void AP_BoardConfig::px4_setup_safety()
|
|||||||
*/
|
*/
|
||||||
void AP_BoardConfig::px4_setup_sbus(void)
|
void AP_BoardConfig::px4_setup_sbus(void)
|
||||||
{
|
{
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
if (px4.sbus_out_rate.get() >= 1) {
|
if (px4.sbus_out_rate.get() >= 1) {
|
||||||
static const struct {
|
static const struct {
|
||||||
uint8_t value;
|
uint8_t value;
|
||||||
@ -180,6 +179,7 @@ void AP_BoardConfig::px4_setup_sbus(void)
|
|||||||
hal.console->printf("Failed to enable SBUS out\n");
|
hal.console->printf("Failed to enable SBUS out\n");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -188,7 +188,7 @@ void AP_BoardConfig::px4_setup_sbus(void)
|
|||||||
*/
|
*/
|
||||||
void AP_BoardConfig::px4_setup_canbus(void)
|
void AP_BoardConfig::px4_setup_canbus(void)
|
||||||
{
|
{
|
||||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 && !defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||||
if (px4.can_enable >= 1) {
|
if (px4.can_enable >= 1) {
|
||||||
if (px4_start_driver(uavcan_main, "uavcan", "start")) {
|
if (px4_start_driver(uavcan_main, "uavcan", "start")) {
|
||||||
hal.console->printf("UAVCAN: started\n");
|
hal.console->printf("UAVCAN: started\n");
|
||||||
@ -215,7 +215,7 @@ void AP_BoardConfig::px4_setup_canbus(void)
|
|||||||
close(fd);
|
close(fd);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // CONFIG_ARCH_BOARD_PX4FMU_V1
|
#endif // CONFIG_HAL_BOARD && !CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||||
}
|
}
|
||||||
|
|
||||||
extern "C" int waitpid(pid_t, int *, int);
|
extern "C" int waitpid(pid_t, int *, int);
|
||||||
@ -507,6 +507,7 @@ void AP_BoardConfig::px4_start_optional_sensors(void)
|
|||||||
|
|
||||||
void AP_BoardConfig::px4_setup_drivers(void)
|
void AP_BoardConfig::px4_setup_drivers(void)
|
||||||
{
|
{
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
px4_start_common_sensors();
|
px4_start_common_sensors();
|
||||||
switch ((px4_board_type)px4.board_type.get()) {
|
switch ((px4_board_type)px4.board_type.get()) {
|
||||||
case PX4_BOARD_PH2SLIM:
|
case PX4_BOARD_PH2SLIM:
|
||||||
@ -525,6 +526,10 @@ void AP_BoardConfig::px4_setup_drivers(void)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
px4_start_optional_sensors();
|
px4_start_optional_sensors();
|
||||||
|
|
||||||
|
// delay for 1 second to give time for drivers to initialise
|
||||||
|
hal.scheduler->delay(1000);
|
||||||
|
#endif // HAL_BOARD_PX4
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -556,9 +561,6 @@ void AP_BoardConfig::px4_setup()
|
|||||||
px4_setup_sbus();
|
px4_setup_sbus();
|
||||||
px4_setup_canbus();
|
px4_setup_canbus();
|
||||||
px4_setup_drivers();
|
px4_setup_drivers();
|
||||||
|
|
||||||
// delay for 1 second to give time for drivers to initialise
|
|
||||||
hal.scheduler->delay(1000);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAL_BOARD_PX4
|
#endif // HAL_BOARD_PX4
|
||||||
|
Loading…
Reference in New Issue
Block a user