HAL_PX4: added rc_bind for DSM bind

This commit is contained in:
Eugene Shamaev 2015-06-10 16:45:26 +10:00 committed by Andrew Tridgell
parent 8cb367eaf8
commit 40a5aa497a
2 changed files with 23 additions and 0 deletions

View File

@ -2,6 +2,9 @@
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
#include "RCInput.h" #include "RCInput.h"
#include <fcntl.h>
#include <unistd.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_hrt.h> #include <drivers/drv_hrt.h>
#include <uORB/uORB.h> #include <uORB/uORB.h>
@ -114,4 +117,22 @@ void PX4RCInput::_timer_tick(void)
perf_end(_perf_rcin); perf_end(_perf_rcin);
} }
bool PX4RCInput::rc_bind(int dsmMode)
{
int fd = open("/dev/px4io", 0);
if (fd == -1) {
hal.console->printf("RCInput: failed to open /dev/px4io\n");
return false;
}
uint32_t mode = (dsmMode == 0) ? DSM2_BIND_PULSES : ((dsmMode == 1) ? DSMX_BIND_PULSES : DSMX8_BIND_PULSES);
int ret = ioctl(fd, DSM_BIND_START, mode);
close(fd);
if (ret != 0) {
hal.console->printf("RCInput: Unable to start DSM bind\n");
return false;
}
return true;
}
#endif #endif

View File

@ -21,6 +21,8 @@ public:
void _timer_tick(void); void _timer_tick(void);
bool rc_bind(int dsmMode);
private: private:
/* override state */ /* override state */
uint16_t _override[RC_INPUT_MAX_CHANNELS]; uint16_t _override[RC_INPUT_MAX_CHANNELS];