mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Periph: 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
82e7476532
commit
d438c8e127
@ -70,20 +70,12 @@ protected:
|
||||
}
|
||||
|
||||
private:
|
||||
GCS_MAVLINK_Periph *chan(const uint8_t ofs) override {
|
||||
if (ofs > _num_gcs) {
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
|
||||
return nullptr;
|
||||
}
|
||||
return (GCS_MAVLINK_Periph *)_chan[ofs];
|
||||
};
|
||||
const GCS_MAVLINK_Periph *chan(const uint8_t ofs) const override {
|
||||
if (ofs > _num_gcs) {
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
|
||||
return nullptr;
|
||||
}
|
||||
return (GCS_MAVLINK_Periph *)_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_Periph);
|
||||
|
||||
MAV_TYPE frame_type() const override { return MAV_TYPE_GENERIC; }
|
||||
uint32_t custom_mode() const override { return 3; } // magic number
|
||||
|
Loading…
Reference in New Issue
Block a user