mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
SITL: fixed build of apm1/apm2 target
This commit is contained in:
parent
761ab5c3e8
commit
e020694c03
@ -1,3 +1,5 @@
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
|
||||
#include "RCInput.h"
|
||||
|
||||
@ -50,3 +52,4 @@ void SITLRCInput::clear_overrides()
|
||||
_override[i] = 0;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
@ -2,6 +2,8 @@
|
||||
#ifndef __AP_HAL_AVR_SITL_RCINPUT_H__
|
||||
#define __AP_HAL_AVR_SITL_RCINPUT_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
#include <AP_HAL_AVR_SITL.h>
|
||||
|
||||
class AVR_SITL::SITLRCInput : public AP_HAL::RCInput {
|
||||
@ -24,5 +26,6 @@ private:
|
||||
uint16_t _override[8];
|
||||
};
|
||||
|
||||
#endif
|
||||
#endif // __AP_HAL_AVR_SITL_RCINPUT_H__
|
||||
|
||||
|
@ -1,3 +1,5 @@
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
|
||||
#include "RCOutput.h"
|
||||
|
||||
@ -43,3 +45,5 @@ void SITLRCOutput::read(uint16_t* period_us, uint8_t len)
|
||||
{
|
||||
memcpy(period_us, _sitlState->pwm_output, len*sizeof(uint16_t));
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -2,6 +2,8 @@
|
||||
#ifndef __AP_HAL_AVR_SITL_RCOUTPUT_H__
|
||||
#define __AP_HAL_AVR_SITL_RCOUTPUT_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
#include <AP_HAL_AVR_SITL.h>
|
||||
|
||||
class AVR_SITL::SITLRCOutput : public AP_HAL::RCOutput {
|
||||
@ -27,5 +29,6 @@ private:
|
||||
uint16_t _freq_hz;
|
||||
};
|
||||
|
||||
#endif
|
||||
#endif // __AP_HAL_AVR_SITL_RCOUTPUT_H__
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user