mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL: re-sync APIs for 4.0 update
This commit is contained in:
parent
4c27e07d06
commit
a426964349
@ -65,6 +65,12 @@ public:
|
|||||||
return attach_interrupt(pin, (AP_HAL::Proc)nullptr, AP_HAL::GPIO::INTERRUPT_NONE);
|
return attach_interrupt(pin, (AP_HAL::Proc)nullptr, AP_HAL::GPIO::INTERRUPT_NONE);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
block waiting for a pin to change. A timeout of 0 means wait
|
||||||
|
forever. Return true on pin change, false on timeout
|
||||||
|
*/
|
||||||
|
virtual bool wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_us) { return false; }
|
||||||
|
|
||||||
/* return true if USB cable is connected */
|
/* return true if USB cable is connected */
|
||||||
virtual bool usb_connected(void) = 0;
|
virtual bool usb_connected(void) = 0;
|
||||||
};
|
};
|
||||||
|
@ -49,7 +49,7 @@ public:
|
|||||||
virtual int16_t read_locked(uint32_t key) { return -1; }
|
virtual int16_t read_locked(uint32_t key) { return -1; }
|
||||||
|
|
||||||
// control optional features
|
// control optional features
|
||||||
virtual bool set_options(uint8_t options) { return options==0; }
|
virtual bool set_options(uint16_t options) { return options==0; }
|
||||||
virtual uint8_t get_options(void) const { return 0; }
|
virtual uint8_t get_options(void) const { return 0; }
|
||||||
|
|
||||||
enum {
|
enum {
|
||||||
@ -57,6 +57,12 @@ public:
|
|||||||
OPTION_TXINV=(1U<<1), // invert TX line
|
OPTION_TXINV=(1U<<1), // invert TX line
|
||||||
OPTION_HDPLEX=(1U<<2), // half-duplex (one-wire) mode
|
OPTION_HDPLEX=(1U<<2), // half-duplex (one-wire) mode
|
||||||
OPTION_SWAP=(1U<<3), // swap RX and TX pins
|
OPTION_SWAP=(1U<<3), // swap RX and TX pins
|
||||||
|
OPTION_PULLDOWN_RX = (1U<<4), // apply pulldown to RX
|
||||||
|
OPTION_PULLUP_RX = (1U<<5), // apply pullup to RX
|
||||||
|
OPTION_PULLDOWN_TX = (1U<<6), // apply pulldown to TX
|
||||||
|
OPTION_PULLUP_TX = (1U<<7), // apply pullup to TX
|
||||||
|
OPTION_NODMA_RX = (1U<<8), // don't use DMA for RX
|
||||||
|
OPTION_NODMA_TX = (1U<<9), // don't use DMA for TX
|
||||||
};
|
};
|
||||||
|
|
||||||
enum flow_control {
|
enum flow_control {
|
||||||
|
@ -42,7 +42,7 @@ public:
|
|||||||
// commands
|
// commands
|
||||||
virtual bool run_debug_shell(AP_HAL::BetterStream *stream) = 0;
|
virtual bool run_debug_shell(AP_HAL::BetterStream *stream) = 0;
|
||||||
|
|
||||||
enum safety_state {
|
enum safety_state : uint8_t {
|
||||||
SAFETY_NONE, SAFETY_DISARMED, SAFETY_ARMED
|
SAFETY_NONE, SAFETY_DISARMED, SAFETY_ARMED
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -55,25 +55,30 @@ public:
|
|||||||
struct PersistentData {
|
struct PersistentData {
|
||||||
float roll_rad, pitch_rad, yaw_rad; // attitude
|
float roll_rad, pitch_rad, yaw_rad; // attitude
|
||||||
int32_t home_lat, home_lon, home_alt_cm; // home position
|
int32_t home_lat, home_lon, home_alt_cm; // home position
|
||||||
bool armed; // true if vehicle was armed
|
uint32_t fault_addr;
|
||||||
enum safety_state safety_state;
|
uint32_t fault_icsr;
|
||||||
|
uint32_t fault_lr;
|
||||||
uint32_t internal_errors;
|
uint32_t internal_errors;
|
||||||
uint32_t internal_error_count;
|
uint16_t internal_error_count;
|
||||||
uint16_t waypoint_num;
|
uint16_t internal_error_last_line;
|
||||||
int8_t scheduler_task;
|
|
||||||
uint16_t last_mavlink_msgid;
|
|
||||||
uint16_t last_mavlink_cmd;
|
|
||||||
uint16_t semaphore_line;
|
|
||||||
uint32_t spi_count;
|
uint32_t spi_count;
|
||||||
uint32_t i2c_count;
|
uint32_t i2c_count;
|
||||||
uint32_t i2c_isr_count;
|
uint32_t i2c_isr_count;
|
||||||
|
uint16_t waypoint_num;
|
||||||
|
uint16_t last_mavlink_msgid;
|
||||||
|
uint16_t last_mavlink_cmd;
|
||||||
|
uint16_t semaphore_line;
|
||||||
uint16_t fault_line;
|
uint16_t fault_line;
|
||||||
uint8_t fault_type;
|
uint8_t fault_type;
|
||||||
uint8_t fault_thd_prio;
|
uint8_t fault_thd_prio;
|
||||||
uint32_t fault_addr;
|
char thread_name4[4];
|
||||||
uint32_t fault_icsr;
|
int8_t scheduler_task;
|
||||||
|
bool armed; // true if vehicle was armed
|
||||||
|
enum safety_state safety_state;
|
||||||
};
|
};
|
||||||
struct PersistentData persistent_data;
|
struct PersistentData persistent_data;
|
||||||
|
// last_persistent_data is only filled in if we've suffered a watchdog reset
|
||||||
|
struct PersistentData last_persistent_data;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
return state of safety switch, if applicable
|
return state of safety switch, if applicable
|
||||||
|
@ -59,7 +59,7 @@
|
|||||||
// allow for static semaphores
|
// allow for static semaphores
|
||||||
#include <AP_HAL_ChibiOS/Semaphores.h>
|
#include <AP_HAL_ChibiOS/Semaphores.h>
|
||||||
#define HAL_Semaphore ChibiOS::Semaphore
|
#define HAL_Semaphore ChibiOS::Semaphore
|
||||||
#define HAL_Semaphore_Recursive ChibiOS::Semaphore_Recursive
|
#define HAL_Semaphore_Recursive ChibiOS::Semaphore
|
||||||
|
|
||||||
/* string names for well known SPI devices */
|
/* string names for well known SPI devices */
|
||||||
#define HAL_BARO_MS5611_NAME "ms5611"
|
#define HAL_BARO_MS5611_NAME "ms5611"
|
||||||
|
@ -335,4 +335,5 @@
|
|||||||
|
|
||||||
#include <AP_HAL_Linux/Semaphores.h>
|
#include <AP_HAL_Linux/Semaphores.h>
|
||||||
#define HAL_Semaphore Linux::Semaphore
|
#define HAL_Semaphore Linux::Semaphore
|
||||||
#define HAL_Semaphore_Recursive Linux::Semaphore_Recursive
|
#define HAL_Semaphore_Recursive Linux::Semaphore
|
||||||
|
|
||||||
|
@ -26,7 +26,7 @@
|
|||||||
// allow for static semaphores
|
// allow for static semaphores
|
||||||
#include <AP_HAL_SITL/Semaphores.h>
|
#include <AP_HAL_SITL/Semaphores.h>
|
||||||
#define HAL_Semaphore HALSITL::Semaphore
|
#define HAL_Semaphore HALSITL::Semaphore
|
||||||
#define HAL_Semaphore_Recursive HALSITL::Semaphore_Recursive
|
#define HAL_Semaphore_Recursive HALSITL::Semaphore
|
||||||
|
|
||||||
#ifndef HAL_BOARD_STORAGE_DIRECTORY
|
#ifndef HAL_BOARD_STORAGE_DIRECTORY
|
||||||
#define HAL_BOARD_STORAGE_DIRECTORY "."
|
#define HAL_BOARD_STORAGE_DIRECTORY "."
|
||||||
|
Loading…
Reference in New Issue
Block a user