mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
HAL_FLYMAPLE: fix for HAL_GPIO_*
This commit is contained in:
parent
3015356671
commit
805d79debe
@ -130,7 +130,7 @@ float FLYMAPLEAnalogSource::_read_average()
|
|||||||
void FLYMAPLEAnalogSource::setup_read() {
|
void FLYMAPLEAnalogSource::setup_read() {
|
||||||
if (_stop_pin != ANALOG_INPUT_NONE) {
|
if (_stop_pin != ANALOG_INPUT_NONE) {
|
||||||
uint8_t digital_pin = hal.gpio->analogPinToDigitalPin(_stop_pin);
|
uint8_t digital_pin = hal.gpio->analogPinToDigitalPin(_stop_pin);
|
||||||
hal.gpio->pinMode(digital_pin, GPIO_OUTPUT);
|
hal.gpio->pinMode(digital_pin, HAL_GPIO_OUTPUT);
|
||||||
hal.gpio->write(digital_pin, 1);
|
hal.gpio->write(digital_pin, 1);
|
||||||
}
|
}
|
||||||
if (_settle_time_ms != 0) {
|
if (_settle_time_ms != 0) {
|
||||||
@ -151,7 +151,7 @@ void FLYMAPLEAnalogSource::setup_read() {
|
|||||||
void FLYMAPLEAnalogSource::stop_read() {
|
void FLYMAPLEAnalogSource::stop_read() {
|
||||||
if (_stop_pin != ANALOG_INPUT_NONE) {
|
if (_stop_pin != ANALOG_INPUT_NONE) {
|
||||||
uint8_t digital_pin = hal.gpio->analogPinToDigitalPin(_stop_pin);
|
uint8_t digital_pin = hal.gpio->analogPinToDigitalPin(_stop_pin);
|
||||||
hal.gpio->pinMode(digital_pin, GPIO_OUTPUT);
|
hal.gpio->pinMode(digital_pin, HAL_GPIO_OUTPUT);
|
||||||
hal.gpio->write(digital_pin, 0);
|
hal.gpio->write(digital_pin, 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -82,9 +82,9 @@ bool FLYMAPLEGPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8
|
|||||||
{
|
{
|
||||||
// Flymaple can only handle RISING, FALLING and CHANGE
|
// Flymaple can only handle RISING, FALLING and CHANGE
|
||||||
ExtIntTriggerMode flymaple_interrupt_mode;
|
ExtIntTriggerMode flymaple_interrupt_mode;
|
||||||
if (mode == GPIO_INTERRUPT_FALLING)
|
if (mode == HAL_GPIO_INTERRUPT_FALLING)
|
||||||
flymaple_interrupt_mode = FALLING;
|
flymaple_interrupt_mode = FALLING;
|
||||||
else if (mode == GPIO_INTERRUPT_RISING)
|
else if (mode == HAL_GPIO_INTERRUPT_RISING)
|
||||||
flymaple_interrupt_mode = RISING;
|
flymaple_interrupt_mode = RISING;
|
||||||
else
|
else
|
||||||
return false;
|
return false;
|
||||||
|
@ -30,16 +30,16 @@ void loop (void) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void setup (void) {
|
void setup (void) {
|
||||||
hal.gpio->pinMode(13, GPIO_OUTPUT);
|
hal.gpio->pinMode(13, HAL_GPIO_OUTPUT);
|
||||||
hal.gpio->write(13, 0);
|
hal.gpio->write(13, 0);
|
||||||
|
|
||||||
a_led = hal.gpio->channel(27);
|
a_led = hal.gpio->channel(27);
|
||||||
b_led = hal.gpio->channel(26);
|
b_led = hal.gpio->channel(26);
|
||||||
c_led = hal.gpio->channel(25);
|
c_led = hal.gpio->channel(25);
|
||||||
|
|
||||||
a_led->mode(GPIO_OUTPUT);
|
a_led->mode(HAL_GPIO_OUTPUT);
|
||||||
b_led->mode(GPIO_OUTPUT);
|
b_led->mode(HAL_GPIO_OUTPUT);
|
||||||
c_led->mode(GPIO_OUTPUT);
|
c_led->mode(HAL_GPIO_OUTPUT);
|
||||||
|
|
||||||
a_led->write(0);
|
a_led->write(0);
|
||||||
b_led->write(0);
|
b_led->write(0);
|
||||||
|
@ -56,7 +56,7 @@ void loop (void) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void setup (void) {
|
void setup (void) {
|
||||||
hal.gpio->pinMode(13, GPIO_OUTPUT);
|
hal.gpio->pinMode(13, HAL_GPIO_OUTPUT);
|
||||||
hal.gpio->write(13, 0);
|
hal.gpio->write(13, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -78,7 +78,7 @@ void loop (void) {
|
|||||||
|
|
||||||
void setup (void) {
|
void setup (void) {
|
||||||
// hal.scheduler->delay(5000);
|
// hal.scheduler->delay(5000);
|
||||||
hal.gpio->pinMode(13, GPIO_OUTPUT);
|
hal.gpio->pinMode(13, HAL_GPIO_OUTPUT);
|
||||||
hal.gpio->write(13, 0);
|
hal.gpio->write(13, 0);
|
||||||
for (uint8_t i=0; i<16; i++) {
|
for (uint8_t i=0; i<16; i++) {
|
||||||
hal.rcout->enable_ch(i);
|
hal.rcout->enable_ch(i);
|
||||||
|
@ -54,7 +54,7 @@ void schedule_toggle_hang(void) {
|
|||||||
|
|
||||||
void setup_pin(int pin_num) {
|
void setup_pin(int pin_num) {
|
||||||
hal.console->printf_P(PSTR("Setup pin %d\r\n"), pin_num);
|
hal.console->printf_P(PSTR("Setup pin %d\r\n"), pin_num);
|
||||||
hal.gpio->pinMode(pin_num,GPIO_OUTPUT);
|
hal.gpio->pinMode(pin_num,HAL_GPIO_OUTPUT);
|
||||||
/* Blink so we can see setup on the logic analyzer.*/
|
/* Blink so we can see setup on the logic analyzer.*/
|
||||||
hal.gpio->write(pin_num,1);
|
hal.gpio->write(pin_num,1);
|
||||||
hal.gpio->write(pin_num,0);
|
hal.gpio->write(pin_num,0);
|
||||||
|
@ -54,7 +54,7 @@ void blink_a3() {
|
|||||||
|
|
||||||
void setup_pin(int pin_num) {
|
void setup_pin(int pin_num) {
|
||||||
hal.console->printf_P(PSTR("Setup pin %d\r\n"), pin_num);
|
hal.console->printf_P(PSTR("Setup pin %d\r\n"), pin_num);
|
||||||
hal.gpio->pinMode(pin_num,GPIO_OUTPUT);
|
hal.gpio->pinMode(pin_num,HAL_GPIO_OUTPUT);
|
||||||
/* Blink so we can see setup on the logic analyzer.*/
|
/* Blink so we can see setup on the logic analyzer.*/
|
||||||
hal.gpio->write(pin_num,1);
|
hal.gpio->write(pin_num,1);
|
||||||
hal.gpio->write(pin_num,0);
|
hal.gpio->write(pin_num,0);
|
||||||
|
Loading…
Reference in New Issue
Block a user