ArduCopter: adjust for renaming of RC_Channel and GCS_MAVLink headers

This commit is contained in:
Peter Barker 2024-12-23 13:26:52 +11:00 committed by Peter Barker
parent c74b0757a4
commit 49020a59c9
6 changed files with 13 additions and 13 deletions

View File

@ -87,9 +87,9 @@
#include <AC_Autorotation/AC_Autorotation.h> // Autorotation controllers
#endif
#include "RC_Channel.h" // RC Channel Library
#include "RC_Channel_Copter.h" // RC Channel Library
#include "GCS_Mavlink.h"
#include "GCS_MAVLink_Copter.h"
#include "GCS_Copter.h"
#include "AP_Rally.h" // Rally point library
#include "AP_Arming.h"

View File

@ -1,7 +1,7 @@
#pragma once
#include <GCS_MAVLink/GCS.h>
#include "GCS_Mavlink.h"
#include "GCS_MAVLink_Copter.h"
class GCS_Copter : public GCS
{

View File

@ -1,6 +1,6 @@
#include "Copter.h"
#include "GCS_Mavlink.h"
#include "GCS_MAVLink_Copter.h"
#include <AP_RPM/AP_RPM_config.h>
#include <AP_EFI/AP_EFI_config.h>

View File

@ -503,42 +503,42 @@ const AP_Param::Info Copter::var_info[] = {
GOBJECTPTR(pos_control, "PSC", AC_PosControl),
// @Group: SR0_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),
#if MAVLINK_COMM_NUM_BUFFERS >= 2
// @Group: SR1_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),
#endif
#if MAVLINK_COMM_NUM_BUFFERS >= 3
// @Group: SR2_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),
#endif
#if MAVLINK_COMM_NUM_BUFFERS >= 4
// @Group: SR3_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),
#endif
#if MAVLINK_COMM_NUM_BUFFERS >= 5
// @Group: SR4_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[4], gcs4, "SR4_", GCS_MAVLINK_Parameters),
#endif
#if MAVLINK_COMM_NUM_BUFFERS >= 6
// @Group: SR5_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[5], gcs5, "SR5_", GCS_MAVLINK_Parameters),
#endif
#if MAVLINK_COMM_NUM_BUFFERS >= 7
// @Group: SR6_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[6], gcs6, "SR6_", GCS_MAVLINK_Parameters),
#endif

View File

@ -3,7 +3,7 @@
#define AP_PARAM_VEHICLE_NAME copter
#include <AP_Common/AP_Common.h>
#include "RC_Channel.h"
#include "RC_Channel_Copter.h"
#include <AP_Proximity/AP_Proximity.h>
#if MODE_FOLLOW_ENABLED

View File

@ -1,6 +1,6 @@
#include "Copter.h"
#include "RC_Channel.h"
#include "RC_Channel_Copter.h"
// defining these two macros and including the RC_Channels_VarInfo header defines the parameter information common to all vehicle types