Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rover: have GCS_MAVLink_Rover unfriend Rover #12073

Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
5 changes: 1 addition & 4 deletions APMrover2/GCS_Rover.h
Expand Up @@ -5,9 +5,8 @@

class GCS_Rover : public GCS
{
friend class Rover; // for access to _chan in parameter declarations

public:
protected:

// return GCS link at offset ofs
GCS_MAVLINK_Rover *chan(const uint8_t ofs) override {
Expand Down Expand Up @@ -36,8 +35,6 @@ class GCS_Rover : public GCS
bool simple_input_active() const override;
bool supersimple_input_active() const override;

protected:

GCS_MAVLINK_Rover *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params,
AP_HAL::UARTDriver &uart) override {
return new GCS_MAVLINK_Rover(params, uart);
Expand Down
8 changes: 4 additions & 4 deletions APMrover2/Parameters.cpp
Expand Up @@ -252,19 +252,19 @@ const AP_Param::Info Rover::var_info[] = {

// @Group: SR0_
// @Path: GCS_Mavlink.cpp
GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),
GOBJECTN(_gcs.chan_params_ref(0), gcs0, "SR0_", GCS_MAVLINK_Parameters),

// @Group: SR1_
// @Path: GCS_Mavlink.cpp
GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),
GOBJECTN(_gcs.chan_params_ref(1), gcs1, "SR1_", GCS_MAVLINK_Parameters),

// @Group: SR2_
// @Path: GCS_Mavlink.cpp
GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),
GOBJECTN(_gcs.chan_params_ref(2), gcs2, "SR2_", GCS_MAVLINK_Parameters),

// @Group: SR3_
// @Path: GCS_Mavlink.cpp
GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),
GOBJECTN(_gcs.chan_params_ref(3), gcs3, "SR3_", GCS_MAVLINK_Parameters),

// @Group: SERIAL
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
Expand Down
10 changes: 10 additions & 0 deletions libraries/GCS_MAVLink/GCS.h
Expand Up @@ -719,6 +719,10 @@ class GCS
void service_statustext(void);
virtual GCS_MAVLINK *chan(const uint8_t ofs) = 0;
virtual const GCS_MAVLINK *chan(const uint8_t ofs) const = 0;

const GCS_MAVLINK_Parameters &chan_params_ref(const uint8_t ofs) const {
return chan_parameters[ofs];
};
// return the number of valid GCS objects
uint8_t num_gcs() const { return _num_gcs; };
void send_message(enum ap_message id);
Expand Down Expand Up @@ -782,6 +786,12 @@ class GCS
virtual void update_vehicle_sensor_status_flags() {}

GCS_MAVLINK_Parameters chan_parameters[MAVLINK_COMM_NUM_BUFFERS];
// The Parameters.cpp files call _gcs.chan_params_ref which
// returns a reference with no bounds checking. So do some
// checking here.
static_assert(ARRAY_SIZE(chan_parameters) >= 4,
"chan_parameters safe to accomodate up to SR3_");

uint8_t _num_gcs;
GCS_MAVLINK *_chan[MAVLINK_COMM_NUM_BUFFERS];

Expand Down