ArduCopter: code-generate chan-fetching methods

A recent PR had to change every single one of these methods, which was kind of unfortunate.

So generate the methods using a #define so the duplication happens at preprocessor-time.
This commit is contained in:
Peter Barker 2022-12-14 12:14:18 +11:00 committed by Peter Barker
parent 6aee69bbda
commit 47876812c5

View File

@ -9,21 +9,12 @@ class GCS_Copter : public GCS
public: public:
// return GCS link at offset ofs // the following define expands to a pair of methods to retrieve a
GCS_MAVLINK_Copter *chan(const uint8_t ofs) override { // pointer to an object of the correct subclass for the link at
if (ofs > _num_gcs) { // offset ofs. These are of the form:
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset); // GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override;
return nullptr; // const GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override const;
} GCS_MAVLINK_CHAN_METHOD_DEFINITIONS(GCS_MAVLINK_Copter);
return (GCS_MAVLINK_Copter *)_chan[ofs];
}
const GCS_MAVLINK_Copter *chan(const uint8_t ofs) const override {
if (ofs > _num_gcs) {
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
return nullptr;
}
return (GCS_MAVLINK_Copter *)_chan[ofs];
}
void update_vehicle_sensor_status_flags(void) override; void update_vehicle_sensor_status_flags(void) override;