Rover: add override keyword where required, fix bad method override

This commit is contained in:
Peter Barker 2018-11-07 22:08:18 +11:00 committed by Andrew Tridgell
parent b0494c1491
commit 86168cd180
2 changed files with 6 additions and 5 deletions

View File

@ -243,7 +243,7 @@ public:
// methods that affect movement of the vehicle in this mode
void update() override;
void calc_throttle(float target_speed, bool nudge_allowed, bool avoidance_enabled);
void calc_throttle(float target_speed, bool nudge_allowed, bool avoidance_enabled) override;
// attributes of the mode
bool is_autopilot_mode() const override { return true; }
@ -252,7 +252,7 @@ public:
float get_distance_to_destination() const override;
// set desired location, heading and speed
void set_desired_location(const struct Location& destination, float next_leg_bearing_cd = MODE_NEXT_HEADING_UNKNOWN);
void set_desired_location(const struct Location& destination, float next_leg_bearing_cd = MODE_NEXT_HEADING_UNKNOWN) override;
bool reached_destination() override;
// heading and speed control
@ -304,7 +304,7 @@ public:
float get_distance_to_destination() const override;
// set desired location, heading and speed
void set_desired_location(const struct Location& destination);
void set_desired_location(const struct Location& destination, float next_leg_bearing_cd = MODE_NEXT_HEADING_UNKNOWN) override;
void set_desired_heading_and_speed(float yaw_angle_cd, float target_speed) override;
// set desired heading-delta, turn-rate and speed

View File

@ -90,10 +90,11 @@ float ModeGuided::get_distance_to_destination() const
}
// set desired location
void ModeGuided::set_desired_location(const struct Location& destination)
void ModeGuided::set_desired_location(const struct Location& destination,
float next_leg_bearing_cd)
{
// call parent
Mode::set_desired_location(destination);
Mode::set_desired_location(destination, next_leg_bearing_cd);
// handle guided specific initialisation and logging
_guided_mode = ModeGuided::Guided_WP;