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

Provide base-class implementation of guided_mode_request function #26112

Merged
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
6 changes: 0 additions & 6 deletions AntennaTracker/GCS_Mavlink.cpp
Expand Up @@ -161,12 +161,6 @@ void GCS_MAVLINK_Tracker::send_pid_tuning()
}
}

bool GCS_MAVLINK_Tracker::handle_guided_request(AP_Mission::Mission_Command&)
{
// do nothing
return false;
}

/*
default stream rates to 1Hz
*/
Expand Down
1 change: 0 additions & 1 deletion AntennaTracker/GCS_Mavlink.h
Expand Up @@ -43,7 +43,6 @@ class GCS_MAVLINK_Tracker : public GCS_MAVLINK
void handle_message_manual_control(const mavlink_message_t &msg);
void handle_message_global_position_int(const mavlink_message_t &msg);
void handle_message_scaled_pressure(const mavlink_message_t &msg);
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
void handle_set_attitude_target(const mavlink_message_t &msg);

void send_global_position_int() override;
Expand Down
9 changes: 0 additions & 9 deletions Blimp/GCS_Mavlink.cpp
Expand Up @@ -407,15 +407,6 @@ const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
MAV_STREAM_TERMINATOR // must have this at end of stream_entries
};

bool GCS_MAVLINK_Blimp::handle_guided_request(AP_Mission::Mission_Command &cmd)
{
// #if MODE_AUTO_ENABLED == ENABLED
// // return blimp.mode_auto.do_guided(cmd);
// #else
return false;
// #endif
}

void GCS_MAVLINK_Blimp::packetReceived(const mavlink_status_t &status,
const mavlink_message_t &msg)
{
Expand Down
1 change: 0 additions & 1 deletion Blimp/GCS_Mavlink.h
Expand Up @@ -53,7 +53,6 @@ class GCS_MAVLINK_Blimp : public GCS_MAVLINK
private:

void handle_message(const mavlink_message_t &msg) override;
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
bool try_send_message(enum ap_message id) override;

void packetReceived(const mavlink_status_t &status,
Expand Down
2 changes: 1 addition & 1 deletion libraries/GCS_MAVLink/GCS.h
Expand Up @@ -1014,7 +1014,7 @@ class GCS_MAVLINK

void send_distance_sensor(const class AP_RangeFinder_Backend *sensor, const uint8_t instance) const;

virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd) = 0;
virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd) { return false; };
virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd) {};
void handle_common_mission_message(const mavlink_message_t &msg);

Expand Down
1 change: 0 additions & 1 deletion libraries/GCS_MAVLink/GCS_Dummy.h
Expand Up @@ -25,7 +25,6 @@ class GCS_MAVLINK_Dummy : public GCS_MAVLINK

uint32_t telem_delay() const override { return 0; }
bool try_send_message(enum ap_message id) override { return true; }
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return true; }
uint8_t sysid_my_gcs() const override { return 1; }

protected:
Expand Down