mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Blimp: 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:
parent
076deb4d97
commit
85d223b9d0
@ -9,23 +9,12 @@ class GCS_Blimp : public GCS
|
|||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
// return GCS link at offset ofs
|
// the following define expands to a pair of methods to retrieve a
|
||||||
GCS_MAVLINK_Blimp *chan(const uint8_t ofs) override
|
// pointer to an object of the correct subclass for the link at
|
||||||
{
|
// offset ofs. These are of the form:
|
||||||
if (ofs > _num_gcs) {
|
// GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override;
|
||||||
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
|
// const GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override const;
|
||||||
return nullptr;
|
GCS_MAVLINK_CHAN_METHOD_DEFINITIONS(GCS_MAVLINK_Blimp);
|
||||||
}
|
|
||||||
return (GCS_MAVLINK_Blimp *)_chan[ofs];
|
|
||||||
}
|
|
||||||
const GCS_MAVLINK_Blimp *chan(const uint8_t ofs) const override
|
|
||||||
{
|
|
||||||
if (ofs > _num_gcs) {
|
|
||||||
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
|
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
return (GCS_MAVLINK_Blimp *)_chan[ofs];
|
|
||||||
}
|
|
||||||
|
|
||||||
void update_vehicle_sensor_status_flags(void) override;
|
void update_vehicle_sensor_status_flags(void) override;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user