Skip to content

Commit

Permalink
GCS_MAVLink: code-generate chan-fetching methods
Browse files Browse the repository at this point in the history
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.
  • Loading branch information
peterbarker committed Dec 14, 2022
1 parent d9dedf3 commit 4e61de7
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 14 deletions.
22 changes: 22 additions & 0 deletions libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,28 @@ void gcs_out_of_space_to_send(mavlink_channel_t chan);
}
#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
class GCS_MAVLINK_Parameters
{
Expand Down
20 changes: 6 additions & 14 deletions libraries/GCS_MAVLink/GCS_Dummy.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,20 +61,12 @@ class GCS_Dummy : public GCS
}

private:
GCS_MAVLINK_Dummy *chan(const uint8_t ofs) override {
if (ofs > _num_gcs) {
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
return nullptr;
}
return (GCS_MAVLINK_Dummy *)_chan[ofs];
};
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];
};
// 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_Dummy);

void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list, uint8_t dest_bitmask) override;

Expand Down

0 comments on commit 4e61de7

Please sign in to comment.