mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: 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
d9dedf3fe8
commit
4e61de7083
|
@ -86,6 +86,28 @@ void gcs_out_of_space_to_send(mavlink_channel_t chan);
|
||||||
}
|
}
|
||||||
#define MAV_STREAM_TERMINATOR { (streams)0, nullptr, 0 }
|
#define MAV_STREAM_TERMINATOR { (streams)0, nullptr, 0 }
|
||||||
|
|
||||||
|
// code generation; avoid each subclass duplicating these two methods
|
||||||
|
// and just changing the name. These methods allow retrieval of
|
||||||
|
// objects specific to the vehicle's subclass, which the vehicle can
|
||||||
|
// then call its own specific methods on
|
||||||
|
#define GCS_MAVLINK_CHAN_METHOD_DEFINITIONS(subclass_name) \
|
||||||
|
subclass_name *chan(const uint8_t ofs) override { \
|
||||||
|
if (ofs > _num_gcs) { \
|
||||||
|
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset); \
|
||||||
|
return nullptr; \
|
||||||
|
} \
|
||||||
|
return (subclass_name *)_chan[ofs]; \
|
||||||
|
} \
|
||||||
|
\
|
||||||
|
const subclass_name *chan(const uint8_t ofs) const override { \
|
||||||
|
if (ofs > _num_gcs) { \
|
||||||
|
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset); \
|
||||||
|
return nullptr; \
|
||||||
|
} \
|
||||||
|
return (subclass_name *)_chan[ofs]; \
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
#define GCS_MAVLINK_NUM_STREAM_RATES 10
|
#define GCS_MAVLINK_NUM_STREAM_RATES 10
|
||||||
class GCS_MAVLINK_Parameters
|
class GCS_MAVLINK_Parameters
|
||||||
{
|
{
|
||||||
|
|
|
@ -61,20 +61,12 @@ protected:
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
GCS_MAVLINK_Dummy *chan(const uint8_t ofs) override {
|
// the following define expands to a pair of methods to retrieve a
|
||||||
if (ofs > _num_gcs) {
|
// pointer to an object of the correct subclass for the link at
|
||||||
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
|
// offset ofs. These are of the form:
|
||||||
return nullptr;
|
// GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override;
|
||||||
}
|
// const GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override const;
|
||||||
return (GCS_MAVLINK_Dummy *)_chan[ofs];
|
GCS_MAVLINK_CHAN_METHOD_DEFINITIONS(GCS_MAVLINK_Dummy);
|
||||||
};
|
|
||||||
const GCS_MAVLINK_Dummy *chan(const uint8_t ofs) const override {
|
|
||||||
if (ofs > _num_gcs) {
|
|
||||||
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
|
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
return (GCS_MAVLINK_Dummy *)_chan[ofs];
|
|
||||||
};
|
|
||||||
|
|
||||||
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list, uint8_t dest_bitmask) override;
|
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list, uint8_t dest_bitmask) override;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue