HAL_PX4: changes for FMUv4
This commit is contained in:
parent
d87219d207
commit
f2358f2441
@ -48,7 +48,7 @@ static const struct {
|
||||
{ 11, 6.6f/4096 }, // analog airspeed input, 2:1 scaling
|
||||
{ 12, 3.3f/4096 }, // analog2, on SPI port pin 3
|
||||
{ 13, 16.8f/4096 }, // analog3, on SPI port pin 4
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
|
||||
{ 2, 3.3f/4096 }, // 3DR Brick voltage, usually 10.1:1
|
||||
// scaled from battery voltage
|
||||
{ 3, 3.3f/4096 }, // 3DR Brick current, usually 17:1 scaled
|
||||
@ -269,7 +269,7 @@ void PX4AnalogIn::_timer_tick(void)
|
||||
if (ret > 0) {
|
||||
// match the incoming channels to the currently active pins
|
||||
for (uint8_t i=0; i<ret/sizeof(buf_adc[0]); i++) {
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
|
||||
if (buf_adc[i].am_channel == 4) {
|
||||
// record the Vcc value for later use in
|
||||
// voltage_average_ratiometric()
|
||||
@ -325,7 +325,7 @@ void PX4AnalogIn::_timer_tick(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
|
||||
// check for new servorail data on FMUv2
|
||||
if (_servorail_handle != -1) {
|
||||
struct servorail_status_s servorail;
|
||||
|
@ -14,7 +14,7 @@
|
||||
// these are virtual pins that read from the ORB
|
||||
#define PX4_ANALOG_ORB_BATTERY_VOLTAGE_PIN 100
|
||||
#define PX4_ANALOG_ORB_BATTERY_CURRENT_PIN 101
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
|
||||
#define PX4_ANALOG_VCC_5V_PIN 4
|
||||
#define PX4_ANALOG_ORB_SERVO_VOLTAGE_PIN 102
|
||||
#define PX4_ANALOG_ORB_SERVO_VRSSI_PIN 103
|
||||
|
@ -58,11 +58,13 @@ void PX4GPIO::init()
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef PX4IO_DEVICE_PATH
|
||||
// also try to setup for the relay pins on the IO board
|
||||
_gpio_io_fd = open(PX4IO_DEVICE_PATH, O_RDWR);
|
||||
if (_gpio_io_fd == -1) {
|
||||
hal.console->printf("GPIO: Unable to open px4io\n");
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void PX4GPIO::pinMode(uint8_t pin, uint8_t output)
|
||||
|
@ -7,6 +7,11 @@
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <pthread.h>
|
||||
|
||||
|
||||
#ifndef RC_INPUT_MAX_CHANNELS
|
||||
#define RC_INPUT_MAX_CHANNELS 18
|
||||
#endif
|
||||
|
||||
class PX4::PX4RCInput : public AP_HAL::RCInput {
|
||||
public:
|
||||
void init(void* machtnichts);
|
||||
|
Loading…
Reference in New Issue
Block a user