mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 22:48:29 -04:00
5472bc4de1
Remove bool return as it's never being used and not supported on PX4.
22 lines
267 B
C++
22 lines
267 B
C++
#pragma once
|
|
|
|
#include "AP_HAL_Linux.h"
|
|
#include "RCInput.h"
|
|
#include <AP_HAL/SPIDevice.h>
|
|
|
|
|
|
namespace Linux {
|
|
|
|
class RCInput_Raspilot : public RCInput
|
|
{
|
|
public:
|
|
void init();
|
|
|
|
private:
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev;
|
|
|
|
void _poll_data(void);
|
|
};
|
|
|
|
}
|