Blimp: adjust for renaming of RC_Channel and GCS_MAVLink headers

This commit is contained in:
Peter Barker 2024-12-23 13:26:53 +11:00 committed by Peter Barker
parent aedaab4724
commit f2a4253ed2
6 changed files with 13 additions and 13 deletions

View File

@ -60,9 +60,9 @@
#include "Fins.h" #include "Fins.h"
#include "Loiter.h" #include "Loiter.h"
#include "RC_Channel.h" // RC Channel Library #include "RC_Channel_Blimp.h" // RC Channel Library
#include "GCS_Mavlink.h" #include "GCS_MAVLink_Blimp.h"
#include "GCS_Blimp.h" #include "GCS_Blimp.h"
#include "AP_Arming.h" #include "AP_Arming.h"

View File

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

View File

@ -1,6 +1,6 @@
#include "Blimp.h" #include "Blimp.h"
#include "GCS_Mavlink.h" #include "GCS_MAVLink_Blimp.h"
#include <AP_RPM/AP_RPM_config.h> #include <AP_RPM/AP_RPM_config.h>
#include <AP_OpticalFlow/AP_OpticalFlow_config.h> #include <AP_OpticalFlow/AP_OpticalFlow_config.h>

View File

@ -292,42 +292,42 @@ const AP_Param::Info Blimp::var_info[] = {
GOBJECT(ins, "INS", AP_InertialSensor), GOBJECT(ins, "INS", AP_InertialSensor),
// @Group: SR0_ // @Group: SR0_
// @Path: GCS_Mavlink.cpp // @Path: GCS_MAVLink_Blimp.cpp
GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters), GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),
#if MAVLINK_COMM_NUM_BUFFERS >= 2 #if MAVLINK_COMM_NUM_BUFFERS >= 2
// @Group: SR1_ // @Group: SR1_
// @Path: GCS_Mavlink.cpp // @Path: GCS_MAVLink_Blimp.cpp
GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters), GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),
#endif #endif
#if MAVLINK_COMM_NUM_BUFFERS >= 3 #if MAVLINK_COMM_NUM_BUFFERS >= 3
// @Group: SR2_ // @Group: SR2_
// @Path: GCS_Mavlink.cpp // @Path: GCS_MAVLink_Blimp.cpp
GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters), GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),
#endif #endif
#if MAVLINK_COMM_NUM_BUFFERS >= 4 #if MAVLINK_COMM_NUM_BUFFERS >= 4
// @Group: SR3_ // @Group: SR3_
// @Path: GCS_Mavlink.cpp // @Path: GCS_MAVLink_Blimp.cpp
GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters), GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),
#endif #endif
#if MAVLINK_COMM_NUM_BUFFERS >= 5 #if MAVLINK_COMM_NUM_BUFFERS >= 5
// @Group: SR4_ // @Group: SR4_
// @Path: GCS_Mavlink.cpp // @Path: GCS_MAVLink_Blimp.cpp
GOBJECTN(_gcs.chan_parameters[4], gcs4, "SR4_", GCS_MAVLINK_Parameters), GOBJECTN(_gcs.chan_parameters[4], gcs4, "SR4_", GCS_MAVLINK_Parameters),
#endif #endif
#if MAVLINK_COMM_NUM_BUFFERS >= 6 #if MAVLINK_COMM_NUM_BUFFERS >= 6
// @Group: SR5_ // @Group: SR5_
// @Path: GCS_Mavlink.cpp // @Path: GCS_MAVLink_Blimp.cpp
GOBJECTN(_gcs.chan_parameters[5], gcs5, "SR5_", GCS_MAVLINK_Parameters), GOBJECTN(_gcs.chan_parameters[5], gcs5, "SR5_", GCS_MAVLINK_Parameters),
#endif #endif
#if MAVLINK_COMM_NUM_BUFFERS >= 7 #if MAVLINK_COMM_NUM_BUFFERS >= 7
// @Group: SR6_ // @Group: SR6_
// @Path: GCS_Mavlink.cpp // @Path: GCS_MAVLink_Blimp.cpp
GOBJECTN(_gcs.chan_parameters[6], gcs6, "SR6_", GCS_MAVLINK_Parameters), GOBJECTN(_gcs.chan_parameters[6], gcs6, "SR6_", GCS_MAVLINK_Parameters),
#endif #endif

View File

@ -3,7 +3,7 @@
#define AP_PARAM_VEHICLE_NAME blimp #define AP_PARAM_VEHICLE_NAME blimp
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include "RC_Channel.h" #include "RC_Channel_Blimp.h"
#include <SRV_Channel/SRV_Channel.h> #include <SRV_Channel/SRV_Channel.h>
// Global parameter class. // Global parameter class.

View File

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