mirror of https://github.com/ArduPilot/ardupilot
Plane: minimal support for inheritting from RC_Channel
This commit is contained in:
parent
0f084ed5bf
commit
9ce02bc504
|
@ -1138,7 +1138,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
|
||||
// @Group: RC
|
||||
// @Path: ../libraries/RC_Channel/RC_Channels.cpp
|
||||
AP_SUBGROUPINFO(rc_channels, "RC", 7, ParametersG2, RC_Channels),
|
||||
AP_SUBGROUPINFO(rc_channels, "RC", 7, ParametersG2, RC_Channels_Plane),
|
||||
|
||||
#if SOARING_ENABLED == ENABLED
|
||||
// @Group: SOAR_
|
||||
|
|
|
@ -518,7 +518,7 @@ public:
|
|||
AP_ICEngine ice_control;
|
||||
|
||||
// RC input channels
|
||||
RC_Channels rc_channels;
|
||||
RC_Channels_Plane rc_channels;
|
||||
|
||||
// control over servo output ranges
|
||||
SRV_Channels servo_channels;
|
||||
|
|
|
@ -40,7 +40,6 @@
|
|||
#include <AP_InertialSensor/AP_InertialSensor.h> // Inertial Sensor Library
|
||||
#include <AP_AccelCal/AP_AccelCal.h> // interface and maths for accelerometer calibration
|
||||
#include <AP_AHRS/AP_AHRS.h> // ArduPilot Mega DCM Library
|
||||
#include <RC_Channel/RC_Channel.h> // RC Channel Library
|
||||
#include <SRV_Channel/SRV_Channel.h>
|
||||
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
|
||||
#include <Filter/Filter.h> // Filter library
|
||||
|
@ -109,6 +108,7 @@
|
|||
// Local modules
|
||||
#include "defines.h"
|
||||
|
||||
#include "RC_Channel.h" // RC Channel Library
|
||||
#include "Parameters.h"
|
||||
#include "avoidance_adsb.h"
|
||||
#include "AP_Arming.h"
|
||||
|
@ -150,6 +150,7 @@ public:
|
|||
friend class AP_AdvancedFailsafe_Plane;
|
||||
friend class AP_Avoidance_Plane;
|
||||
friend class GCS_Plane;
|
||||
friend class RC_Channels_Plane;
|
||||
|
||||
Plane(void);
|
||||
|
||||
|
|
|
@ -0,0 +1,17 @@
|
|||
#include "Plane.h"
|
||||
|
||||
#include "RC_Channel.h"
|
||||
|
||||
// defining these two macros and including the RC_Channels_VarInfo
|
||||
// header defines the parameter information common to all vehicle
|
||||
// types
|
||||
#define RC_CHANNELS_SUBCLASS RC_Channels_Plane
|
||||
#define RC_CHANNEL_SUBCLASS RC_Channel_Plane
|
||||
|
||||
#include <RC_Channel/RC_Channels_VarInfo.h>
|
||||
|
||||
// note that this callback is not presently used on Plane:
|
||||
int8_t RC_Channels_Plane::flight_mode_channel_number() const
|
||||
{
|
||||
return plane.g.flight_mode_channel.get();
|
||||
}
|
|
@ -0,0 +1,33 @@
|
|||
#pragma once
|
||||
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
|
||||
class RC_Channel_Plane : public RC_Channel
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
protected:
|
||||
|
||||
private:
|
||||
|
||||
};
|
||||
|
||||
class RC_Channels_Plane : public RC_Channels
|
||||
{
|
||||
public:
|
||||
|
||||
RC_Channel_Plane obj_channels[NUM_RC_CHANNELS];
|
||||
RC_Channel_Plane *channel(const uint8_t chan) override {
|
||||
if (chan > NUM_RC_CHANNELS) {
|
||||
return nullptr;
|
||||
}
|
||||
return &obj_channels[chan];
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
// note that these callbacks are not presently used on Plane:
|
||||
int8_t flight_mode_channel_number() const override;
|
||||
|
||||
};
|
|
@ -174,7 +174,7 @@ void Plane::rudder_arm_disarm_check()
|
|||
|
||||
void Plane::read_radio()
|
||||
{
|
||||
if (!RC_Channels::read_input()) {
|
||||
if (!rc().read_input()) {
|
||||
control_failsafe();
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -84,6 +84,9 @@ void Plane::init_ardupilot()
|
|||
BoardConfig_CAN.init();
|
||||
#endif
|
||||
|
||||
// initialise rc channels including setting mode
|
||||
rc().init();
|
||||
|
||||
relay.init();
|
||||
|
||||
// initialise notify system
|
||||
|
|
Loading…
Reference in New Issue