5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-02-13 03:13:57 -04:00

AP_HAL: support SBusOut

rename enable_sbus_out to enable_px4io_sbus_out
This commit is contained in:
Mark Whitehorn 2017-11-22 10:38:34 -07:00 committed by Andrew Tridgell
parent 9c91a959aa
commit 66c4b7d986
3 changed files with 12 additions and 3 deletions

View File

@ -1,6 +1,7 @@
#pragma once
#include "AP_HAL_Namespace.h"
#include <stdint.h>
#define RC_OUTPUT_MIN_PULSEWIDTH 400
#define RC_OUTPUT_MAX_PULSEWIDTH 2100
@ -114,9 +115,9 @@ public:
virtual float scale_esc_to_unity(uint16_t pwm) { return 0; }
/*
enable SBUS out at the given rate
enable PX4IO SBUS out at the given rate
*/
virtual bool enable_sbus_out(uint16_t rate_hz) { return false; }
virtual bool enable_px4io_sbus_out(uint16_t rate_hz) { return false; }
/*
* Optional method to control the update of the motors. Derived classes

View File

@ -18,7 +18,7 @@
#include "utility/print_vprintf.h"
#include "UARTDriver.h"
/*
/*
BetterStream method implementations
These are implemented in AP_HAL to ensure consistent behaviour on
all boards, although they can be overridden by a port

View File

@ -45,6 +45,14 @@ public:
virtual void set_flow_control(enum flow_control flow_control_setting) {};
virtual enum flow_control get_flow_control(void) { return FLOW_CONTROL_DISABLE; }
virtual void configure_parity(uint8_t v){};
virtual void set_stop_bits(int n){};
/* unbuffered writes bypass the ringbuffer and go straight to the
* file descriptor
*/
virtual bool set_unbuffered_writes(bool on){ return false; };
/* Implementations of BetterStream virtual methods. These are
* provided by AP_HAL to ensure consistency between ports to
* different boards