Rover: use AR_WPNAV_HEADING_UNKNOWN in place of local define

This commit is contained in:
Randy Mackay 2019-05-04 15:49:28 +09:00
parent 1f2500d268
commit 39418abafb
2 changed files with 8 additions and 9 deletions

View File

@ -5,11 +5,10 @@
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Math/AP_Math.h>
#include <AP_Mission/AP_Mission.h>
#include <AR_WPNav/AR_WPNav.h>
#include "defines.h"
#define MODE_NEXT_HEADING_UNKNOWN 99999.0f // used to indicate to set_desired_location method that next leg's heading is unknown
// pre-define ModeRTL so Auto can appear higher in this file
class ModeRTL;
@ -104,9 +103,9 @@ public:
// return distance (in meters) to destination
virtual float get_distance_to_destination() const { return 0.0f; }
// set desired location and speed (used in RTL, Guided, Auto)
// set desired location (used in Guided, Auto)
// next_leg_bearing_cd should be heading to the following waypoint (used to slow the vehicle in order to make the turn)
virtual void set_desired_location(const struct Location& destination, float next_leg_bearing_cd = MODE_NEXT_HEADING_UNKNOWN);
virtual void set_desired_location(const struct Location& destination, float next_leg_bearing_cd = AR_WPNAV_HEADING_UNKNOWN);
// true if vehicle has reached desired location. defaults to true because this is normally used by missions and we do not want the mission to become stuck
virtual bool reached_destination() const { return true; }
@ -252,8 +251,8 @@ public:
// return distance (in meters) to destination
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) override;
// set desired location
void set_desired_location(const struct Location& destination, float next_leg_bearing_cd = AR_WPNAV_HEADING_UNKNOWN) override;
bool reached_destination() const override;
// heading and speed control
@ -367,7 +366,7 @@ public:
bool reached_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) override;
void set_desired_location(const struct Location& destination, float next_leg_bearing_cd = AR_WPNAV_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

@ -494,9 +494,9 @@ void ModeAuto::do_nav_wp(const AP_Mission::Mission_Command& cmd, bool always_sto
// get heading to following waypoint (auto mode reduces speed to allow corning without large overshoot)
// in case of non-zero loiter duration, we provide heading-unknown to signal we should stop at the point
float next_leg_bearing_cd = MODE_NEXT_HEADING_UNKNOWN;
float next_leg_bearing_cd = AR_WPNAV_HEADING_UNKNOWN;
if (!always_stop_at_destination && loiter_duration == 0) {
next_leg_bearing_cd = mission.get_next_ground_course_cd(MODE_NEXT_HEADING_UNKNOWN);
next_leg_bearing_cd = mission.get_next_ground_course_cd(AR_WPNAV_HEADING_UNKNOWN);
}
// retrieve and sanitize target location