HAL_Linux: update to match plane 3.9.0beta6

This commit is contained in:
Andrew Tridgell 2018-08-01 18:58:23 +10:00 committed by Randy Mackay
parent 524dfdf217
commit faa937e41d
15 changed files with 72 additions and 34 deletions

View File

@ -1,7 +1,7 @@
#pragma once
#include "AP_HAL_Linux.h"
#include <AP_ADC/AP_ADC.h>
#include <AP_ADC/AP_ADC_ADS1115.h>
#define ADS1115_ADC_MAX_CHANNELS 6

View File

@ -1,7 +1,6 @@
#pragma once
#include "AP_HAL_Linux.h"
#include <AP_ADC/AP_ADC.h>
#include <fcntl.h>
#include <unistd.h>

View File

@ -77,12 +77,6 @@ void GPIO_BBB::pinMode(uint8_t pin, uint8_t output)
}
}
int8_t GPIO_BBB::analogPinToDigitalPin(uint8_t pin)
{
return -1;
}
uint8_t GPIO_BBB::read(uint8_t pin) {
uint8_t bank = pin/32;

View File

@ -122,7 +122,6 @@ public:
GPIO_BBB();
void init();
void pinMode(uint8_t pin, uint8_t output);
int8_t analogPinToDigitalPin(uint8_t pin);
uint8_t read(uint8_t pin);
void write(uint8_t pin, uint8_t value);
void toggle(uint8_t pin);

View File

@ -30,6 +30,7 @@
#define GPIO_SET_HIGH *(_gpio+7) // sets bits which are 1
#define GPIO_SET_LOW *(_gpio+10) // clears bits which are 1
#define GPIO_GET(g) (*(_gpio+13)&(1<<g)) // 0 if LOW, (1<<g) if HIGH
#define GPIO_RPI_MAX_NUMBER_PINS 32
using namespace Linux;
@ -91,13 +92,11 @@ void GPIO_RPI::pinMode(uint8_t pin, uint8_t output, uint8_t alt)
}
}
int8_t GPIO_RPI::analogPinToDigitalPin(uint8_t pin)
{
return -1;
}
uint8_t GPIO_RPI::read(uint8_t pin)
{
if (pin >= GPIO_RPI_MAX_NUMBER_PINS) {
return 0;
}
uint32_t value = GPIO_GET(pin);
return value ? 1: 0;
}

View File

@ -49,7 +49,6 @@ public:
void init();
void pinMode(uint8_t pin, uint8_t output);
void pinMode(uint8_t pin, uint8_t output, uint8_t alt);
int8_t analogPinToDigitalPin(uint8_t pin);
uint8_t read(uint8_t pin);
void write(uint8_t pin, uint8_t value);
void toggle(uint8_t pin);

View File

@ -171,11 +171,6 @@ void GPIO_Sysfs::toggle(uint8_t vpin)
write(vpin, !read(vpin));
}
int8_t GPIO_Sysfs::analogPinToDigitalPin(uint8_t vpin)
{
return -1;
}
AP_HAL::DigitalSource* GPIO_Sysfs::channel(uint16_t vpin)
{
assert_vpin(vpin, n_pins, nullptr);

View File

@ -49,11 +49,6 @@ public:
*/
AP_HAL::DigitalSource *channel(uint16_t vpin) override;
/*
* Currently this function always returns -1.
*/
int8_t analogPinToDigitalPin(uint8_t vpin) override;
/*
* Currently this function always returns false.
*/

View File

@ -32,7 +32,7 @@ using namespace Linux;
static void catch_sigbus(int sig)
{
AP_HAL::panic("RCOutputAioPRU.cpp:SIGBUS error gernerated\n");
AP_HAL::panic("RCOutputAioPRU.cpp:SIGBUS error generated\n");
}
void RCOutput_AioPRU::init()
{

View File

@ -23,7 +23,7 @@ static const uint8_t chan_pru_map[]= {10,8,11,9,7,6,5,4,3,2,1,0};
static void catch_sigbus(int sig)
{
AP_HAL::panic("RCOutput.cpp:SIGBUS error gernerated\n");
AP_HAL::panic("RCOutput.cpp:SIGBUS error generated\n");
}
void RCOutput_PRU::init()
{

View File

@ -31,7 +31,7 @@ using namespace Linux;
static void catch_sigbus(int sig)
{
AP_HAL::panic("RCOutput.cpp:SIGBUS error gernerated\n");
AP_HAL::panic("RCOutput.cpp:SIGBUS error generated\n");
}
void RCOutput_ZYNQ::init()
{

View File

@ -10,6 +10,7 @@
#include <unistd.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include "RCInput.h"
@ -26,6 +27,7 @@ using namespace Linux;
extern const AP_HAL::HAL& hal;
#define APM_LINUX_MAX_PRIORITY 20
#define APM_LINUX_TIMER_PRIORITY 15
#define APM_LINUX_UART_PRIORITY 14
#define APM_LINUX_RCIN_PRIORITY 13
@ -146,17 +148,12 @@ void Scheduler::delay(uint16_t ms)
return;
}
if (!in_main_thread()) {
fprintf(stderr, "Scheduler::delay() called outside main thread\n");
return;
}
uint64_t start = AP_HAL::millis64();
while ((AP_HAL::millis64() - start) < ms) {
// this yields the CPU to other apps
microsleep(1000);
if (_min_delay_cb_ms <= ms) {
if (in_main_thread() && _min_delay_cb_ms <= ms) {
call_delay_cb();
}
}
@ -356,3 +353,52 @@ void Scheduler::teardown()
_uart_thread.join();
_tonealarm_thread.join();
}
/*
create a new thread
*/
bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_t stack_size, priority_base base, int8_t priority)
{
Thread *thread = new Thread{(Thread::task_t)proc};
if (!thread) {
return false;
}
uint8_t thread_priority = APM_LINUX_IO_PRIORITY;
static const struct {
priority_base base;
uint8_t p;
} priority_map[] = {
{ PRIORITY_BOOST, APM_LINUX_MAIN_PRIORITY},
{ PRIORITY_MAIN, APM_LINUX_MAIN_PRIORITY},
{ PRIORITY_SPI, AP_LINUX_SENSORS_SCHED_PRIO},
{ PRIORITY_I2C, AP_LINUX_SENSORS_SCHED_PRIO},
{ PRIORITY_CAN, APM_LINUX_TIMER_PRIORITY},
{ PRIORITY_TIMER, APM_LINUX_TIMER_PRIORITY},
{ PRIORITY_RCIN, APM_LINUX_RCIN_PRIORITY},
{ PRIORITY_IO, APM_LINUX_IO_PRIORITY},
{ PRIORITY_UART, APM_LINUX_UART_PRIORITY},
{ PRIORITY_STORAGE, APM_LINUX_IO_PRIORITY},
};
for (uint8_t i=0; i<ARRAY_SIZE(priority_map); i++) {
if (priority_map[i].base == base) {
thread_priority = constrain_int16(priority_map[i].p + priority, 1, APM_LINUX_MAX_PRIORITY);
break;
}
}
thread->set_stack_size(stack_size);
/*
* We should probably store the thread handlers and join() when exiting,
* but let's the thread manage itself for now.
*/
thread->set_auto_free(true);
if (!thread->start(name, SCHED_FIFO, thread_priority)) {
delete thread;
return false;
}
return true;
}

View File

@ -47,6 +47,11 @@ public:
void teardown();
/*
create a new thread
*/
bool thread_create(AP_HAL::MemberProc, const char *name, uint32_t stack_size, priority_base base, int8_t priority) override;
private:
class SchedulerThread : public PeriodicThread {
public:

View File

@ -40,6 +40,10 @@ void *Thread::_run_trampoline(void *arg)
thread->_poison_stack();
thread->_run();
if (thread->_auto_free) {
delete thread;
}
return nullptr;
}

View File

@ -45,6 +45,8 @@ public:
bool set_stack_size(size_t stack_size);
void set_auto_free(bool auto_free) { _auto_free = auto_free; }
virtual bool stop() { return false; }
bool join();
@ -64,6 +66,7 @@ protected:
task_t _task;
bool _started = false;
bool _should_exit = false;
bool _auto_free = false;
pthread_t _ctx = 0;
struct stack_debug {