mirror of https://github.com/ArduPilot/ardupilot
Tracker: minimal support for inheritting from RC_Channel
This commit is contained in:
parent
1ba0901e51
commit
f79b4b5d63
|
@ -300,8 +300,8 @@ const AP_Param::Info Tracker::var_info[] = {
|
||||||
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
|
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
|
||||||
GOBJECT(notify, "NTF_", AP_Notify),
|
GOBJECT(notify, "NTF_", AP_Notify),
|
||||||
|
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channels.cpp
|
// @Path: RC_Channels.cpp
|
||||||
GOBJECT(rc_channels, "RC", RC_Channels),
|
GOBJECT(rc_channels, "RC", RC_Channels_Tracker),
|
||||||
|
|
||||||
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
|
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
|
||||||
GOBJECT(servo_channels, "SERVO", SRV_Channels),
|
GOBJECT(servo_channels, "SERVO", SRV_Channels),
|
||||||
|
|
|
@ -0,0 +1,71 @@
|
||||||
|
#include "Tracker.h"
|
||||||
|
|
||||||
|
#include "RC_Channel.h"
|
||||||
|
|
||||||
|
const AP_Param::GroupInfo RC_Channels::var_info[] = {
|
||||||
|
// @Group: 1_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[0], "1_", 1, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 2_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[1], "2_", 2, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 3_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[2], "3_", 3, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 4_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[3], "4_", 4, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 5_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[4], "5_", 5, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 6_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[5], "6_", 6, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 7_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[6], "7_", 7, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 8_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[7], "8_", 8, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 9_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[8], "9_", 9, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 10_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[9], "10_", 10, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 11_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[10], "11_", 11, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 12_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[11], "12_", 12, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 13_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[12], "13_", 13, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 14_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[13], "14_", 14, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 15_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[14], "15_", 15, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
// @Group: 16_
|
||||||
|
// @Path: RC_Channel.cpp
|
||||||
|
AP_SUBGROUPINFO(obj_channels[15], "16_", 16, RC_Channels_Tracker, RC_Channel_Tracker),
|
||||||
|
|
||||||
|
AP_GROUPEND
|
||||||
|
};
|
|
@ -0,0 +1,30 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <RC_Channel/RC_Channel.h>
|
||||||
|
|
||||||
|
class RC_Channel_Tracker : public RC_Channel
|
||||||
|
{
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
protected:
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
class RC_Channels_Tracker : public RC_Channels
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
|
||||||
|
RC_Channel_Tracker obj_channels[NUM_RC_CHANNELS];
|
||||||
|
RC_Channel_Tracker *channel(const uint8_t chan) override {
|
||||||
|
if (chan > NUM_RC_CHANNELS) {
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
return &obj_channels[chan];
|
||||||
|
}
|
||||||
|
|
||||||
|
protected:
|
||||||
|
|
||||||
|
};
|
|
@ -55,7 +55,6 @@
|
||||||
#include <AP_Notify/AP_Notify.h> // Notify library
|
#include <AP_Notify/AP_Notify.h> // Notify library
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
|
||||||
#include <AP_Airspeed/AP_Airspeed.h>
|
#include <AP_Airspeed/AP_Airspeed.h>
|
||||||
#include <RC_Channel/RC_Channel.h>
|
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
|
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
|
||||||
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
||||||
|
@ -66,6 +65,7 @@
|
||||||
#include "config.h"
|
#include "config.h"
|
||||||
#include "defines.h"
|
#include "defines.h"
|
||||||
|
|
||||||
|
#include "RC_Channel.h"
|
||||||
#include "Parameters.h"
|
#include "Parameters.h"
|
||||||
#include "GCS_Mavlink.h"
|
#include "GCS_Mavlink.h"
|
||||||
#include "GCS_Tracker.h"
|
#include "GCS_Tracker.h"
|
||||||
|
@ -127,7 +127,7 @@ private:
|
||||||
/**
|
/**
|
||||||
antenna control channels
|
antenna control channels
|
||||||
*/
|
*/
|
||||||
RC_Channels rc_channels;
|
RC_Channels_Tracker rc_channels;
|
||||||
SRV_Channels servo_channels;
|
SRV_Channels servo_channels;
|
||||||
|
|
||||||
LowPassFilterFloat yaw_servo_out_filt;
|
LowPassFilterFloat yaw_servo_out_filt;
|
||||||
|
|
|
@ -0,0 +1,13 @@
|
||||||
|
/* dummy methods to avoid having to link against AP_Camera */
|
||||||
|
|
||||||
|
#include <AP_Camera/AP_Camera.h>
|
||||||
|
|
||||||
|
namespace AP {
|
||||||
|
AP_Camera *camera() {
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
void AP_Camera::take_picture()
|
||||||
|
{
|
||||||
|
}
|
|
@ -4,5 +4,5 @@
|
||||||
|
|
||||||
void Tracker::read_radio()
|
void Tracker::read_radio()
|
||||||
{
|
{
|
||||||
RC_Channels::read_input();
|
rc().read_input();
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue