mirror of https://github.com/ArduPilot/ardupilot
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:
parent
6aee69bbda
commit
47876812c5
|
@ -9,21 +9,12 @@ class GCS_Copter : public GCS
|
|||
|
||||
public:
|
||||
|
||||
// return GCS link at offset ofs
|
||||
GCS_MAVLINK_Copter *chan(const uint8_t ofs) override {
|
||||
if (ofs > _num_gcs) {
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
|
||||
return nullptr;
|
||||
}
|
||||
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];
|
||||
}
|
||||
// the following define expands to a pair of methods to retrieve a
|
||||
// pointer to an object of the correct subclass for the link at
|
||||
// offset ofs. These are of the form:
|
||||
// GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override;
|
||||
// const GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override const;
|
||||
GCS_MAVLINK_CHAN_METHOD_DEFINITIONS(GCS_MAVLINK_Copter);
|
||||
|
||||
void update_vehicle_sensor_status_flags(void) override;
|
||||
|
||||
|
|
Loading…
Reference in New Issue