2016-07-21 21:58:02 -03:00
|
|
|
|
|
|
|
#include "GPIO.h"
|
|
|
|
|
|
|
|
using namespace HALSITL;
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2018-06-10 03:33:38 -03:00
|
|
|
#define SITL_WOW_ALTITUDE 0.01
|
|
|
|
|
2016-07-21 21:58:02 -03:00
|
|
|
void GPIO::init()
|
|
|
|
{}
|
|
|
|
|
|
|
|
void GPIO::pinMode(uint8_t pin, uint8_t output)
|
|
|
|
{}
|
|
|
|
|
|
|
|
uint8_t GPIO::read(uint8_t pin)
|
|
|
|
{
|
2017-01-09 08:25:29 -04:00
|
|
|
if (!_sitlState->_sitl) {
|
2016-07-21 21:58:02 -03:00
|
|
|
return 0;
|
|
|
|
}
|
2018-06-10 03:33:38 -03:00
|
|
|
|
|
|
|
// weight on wheels pin support
|
|
|
|
if (pin == _sitlState->_sitl->wow_pin.get()) {
|
|
|
|
return _sitlState->_sitl->state.altitude < SITL_WOW_ALTITUDE ? 1 : 0;
|
|
|
|
}
|
|
|
|
|
2018-04-18 00:33:48 -03:00
|
|
|
uint16_t mask = static_cast<uint16_t>(_sitlState->_sitl->pin_mask.get());
|
|
|
|
return static_cast<uint16_t>((mask & (1U << pin)) ? 1 : 0);
|
2016-07-21 21:58:02 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void GPIO::write(uint8_t pin, uint8_t value)
|
|
|
|
{
|
2017-01-09 08:25:29 -04:00
|
|
|
if (!_sitlState->_sitl) {
|
2016-07-21 21:58:02 -03:00
|
|
|
return;
|
|
|
|
}
|
2018-04-18 00:33:48 -03:00
|
|
|
uint16_t mask = static_cast<uint16_t>(_sitlState->_sitl->pin_mask.get());
|
|
|
|
uint16_t new_mask = mask;
|
2018-06-10 03:33:38 -03:00
|
|
|
|
|
|
|
if (pin == _sitlState->_sitl->wow_pin.get()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-07-21 21:58:02 -03:00
|
|
|
if (value) {
|
2017-01-09 08:25:29 -04:00
|
|
|
new_mask |= (1U << pin);
|
2016-07-21 21:58:02 -03:00
|
|
|
} else {
|
2017-01-09 08:25:29 -04:00
|
|
|
new_mask &= ~(1U << pin);
|
2016-07-21 23:23:00 -03:00
|
|
|
}
|
|
|
|
if (mask != new_mask) {
|
2017-01-09 08:25:29 -04:00
|
|
|
_sitlState->_sitl->pin_mask.set_and_notify(new_mask);
|
2016-07-21 21:58:02 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void GPIO::toggle(uint8_t pin)
|
|
|
|
{
|
|
|
|
write(pin, !read(pin));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Alternative interface: */
|
|
|
|
AP_HAL::DigitalSource* GPIO::channel(uint16_t n) {
|
2018-04-18 00:33:48 -03:00
|
|
|
if (n < 16) { // (ie. sizeof(pin_mask)*8)
|
2017-01-09 08:25:29 -04:00
|
|
|
return new DigitalSource(static_cast<uint8_t>(n));
|
|
|
|
} else {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
|
2016-07-21 21:58:02 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
bool GPIO::usb_connected(void)
|
|
|
|
{
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2017-01-09 08:25:29 -04:00
|
|
|
DigitalSource::DigitalSource(uint8_t pin) :
|
|
|
|
_pin(pin)
|
2016-07-21 21:58:02 -03:00
|
|
|
{}
|
|
|
|
|
|
|
|
void DigitalSource::mode(uint8_t output)
|
|
|
|
{}
|
|
|
|
|
|
|
|
uint8_t DigitalSource::read()
|
|
|
|
{
|
2017-01-09 08:25:29 -04:00
|
|
|
return hal.gpio->read(_pin);
|
2016-07-21 21:58:02 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void DigitalSource::write(uint8_t value)
|
|
|
|
{
|
2017-01-09 08:25:29 -04:00
|
|
|
value = static_cast<uint8_t>(value ? 1 : 0);
|
|
|
|
return hal.gpio->write(_pin, value);
|
2016-07-21 21:58:02 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void DigitalSource::toggle()
|
|
|
|
{
|
2017-01-09 08:25:29 -04:00
|
|
|
return hal.gpio->write(_pin, !hal.gpio->read(_pin));
|
2016-07-21 21:58:02 -03:00
|
|
|
}
|