ardupilot/libraries/AP_HAL_SITL/RCInput.cpp

96 lines
2.1 KiB
C++
Raw Permalink Normal View History

#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH)
2012-12-17 23:56:21 -04:00
#include "RCInput.h"
2018-07-23 23:46:31 -03:00
#include <SITL/SITL.h>
#include <AP_RCProtocol/AP_RCProtocol.h>
2012-12-17 23:56:21 -04:00
#ifdef SFML_JOYSTICK
#ifdef HAVE_SFML_GRAPHICS_HPP
#include <SFML/Window/Joystick.hpp>
#elif HAVE_SFML_GRAPHIC_H
#include <SFML/Window/Joystick.h>
#endif
#endif // SFML_JOYSTICK
using namespace HALSITL;
2012-12-17 23:56:21 -04:00
extern const AP_HAL::HAL& hal;
void RCInput::init()
2012-12-17 23:56:21 -04:00
{
AP::RC().init();
2012-12-17 23:56:21 -04:00
}
bool RCInput::new_input()
{
if (!using_rc_protocol) {
if (AP::RC().new_input()) {
using_rc_protocol = true;
}
}
if (using_rc_protocol) {
return AP::RC().new_input();
}
if (_sitlState->new_rc_input) {
_sitlState->new_rc_input = false;
return true;
}
return false;
2012-12-17 23:56:21 -04:00
}
uint16_t RCInput::read(uint8_t ch)
{
if (using_rc_protocol) {
return AP::RC().read(ch);
}
2018-07-23 23:46:31 -03:00
if (ch >= num_channels()) {
return 0;
}
#ifdef SFML_JOYSTICK
SITL::SITL *_sitl = AP::sitl();
if (_sitl) {
const sf::Joystick::Axis axis = sf::Joystick::Axis(_sitl->sfml_joystick_axis[ch].get());
const unsigned int stickID = _sitl->sfml_joystick_id;
if (sf::Joystick::hasAxis(stickID, axis)) {
return (constrain_float(sf::Joystick::getAxisPosition(stickID, axis) + 100, 0, 200) * 5) + 1000;
} else {
return 0;
}
} else {
return 0;
}
#else
2016-05-03 23:50:02 -03:00
return _sitlState->pwm_input[ch];
#endif
2012-12-17 23:56:21 -04:00
}
uint8_t RCInput::read(uint16_t* periods, uint8_t len)
{
2018-07-23 23:46:31 -03:00
if (len > num_channels()) {
len = num_channels();
}
for (uint8_t i=0; i < len; i++) {
2016-05-03 23:50:02 -03:00
periods[i] = read(i);
2012-12-17 23:56:21 -04:00
}
return len;
2012-12-17 23:56:21 -04:00
}
2018-07-23 23:46:31 -03:00
uint8_t RCInput::num_channels()
{
if (using_rc_protocol) {
return AP::RC().num_channels();
}
2018-07-23 23:46:31 -03:00
SITL::SITL *_sitl = AP::sitl();
if (_sitl) {
#ifdef SFML_JOYSTICK
return (sf::Joystick::isConnected(_sitl->sfml_joystick_id.get())) ? ARRAY_SIZE(_sitl->sfml_joystick_axis) : 0;
#else
2018-07-23 23:46:31 -03:00
return MIN(_sitl->rc_chancount.get(), SITL_RC_INPUT_CHANNELS);
#endif // SFML_JOYSTICK
2018-07-23 23:46:31 -03:00
}
return SITL_RC_INPUT_CHANNELS;
}
2012-12-18 05:04:47 -04:00
#endif