mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Plane: minor signed/type fixups
This commit is contained in:
parent
32d702e912
commit
ebb7f27962
@ -501,7 +501,7 @@ static int32_t nav_pitch_cd;
|
||||
uint32_t wp_distance;
|
||||
|
||||
// Distance between previous and next waypoint. Meters
|
||||
static int32_t wp_totalDistance;
|
||||
static uint32_t wp_totalDistance;
|
||||
|
||||
// event control state
|
||||
enum event_type {
|
||||
|
@ -359,7 +359,7 @@ static bool verify_nav_wp()
|
||||
{
|
||||
hold_course = -1;
|
||||
update_crosstrack();
|
||||
if (wp_distance <= (unsigned)max(g.waypoint_radius,0)) {
|
||||
if (wp_distance <= (uint32_t)max(g.waypoint_radius,0)) {
|
||||
gcs_send_text_fmt(PSTR("Reached Waypoint #%i dist %um"),
|
||||
(unsigned)nav_command_index,
|
||||
(unsigned)get_distance(¤t_loc, &next_WP));
|
||||
@ -416,7 +416,7 @@ static bool verify_loiter_turns()
|
||||
|
||||
static bool verify_RTL()
|
||||
{
|
||||
if (wp_distance <= (unsigned)max(g.waypoint_radius,0)) {
|
||||
if (wp_distance <= (uint32_t)max(g.waypoint_radius,0)) {
|
||||
gcs_send_text_P(SEVERITY_LOW,PSTR("Reached home"));
|
||||
return true;
|
||||
}else{
|
||||
|
@ -148,11 +148,11 @@ static void update_loiter()
|
||||
{
|
||||
float power;
|
||||
|
||||
if(wp_distance <= (unsigned)max(g.loiter_radius,0)) {
|
||||
if(wp_distance <= (uint32_t)max(g.loiter_radius,0)) {
|
||||
power = float(wp_distance) / float(g.loiter_radius);
|
||||
power = constrain(power, 0.5, 1);
|
||||
nav_bearing_cd += 9000.0 * (2.0 + power);
|
||||
} else if(wp_distance < (unsigned long)max((g.loiter_radius + LOITER_RANGE),0)) {
|
||||
} else if(wp_distance < (uint32_t)max((g.loiter_radius + LOITER_RANGE),0)) {
|
||||
power = -((float)(wp_distance - g.loiter_radius - LOITER_RANGE) / LOITER_RANGE);
|
||||
power = constrain(power, 0.5, 1); //power = constrain(power, 0, 1);
|
||||
nav_bearing_cd -= power * 9000;
|
||||
@ -191,7 +191,7 @@ static void update_crosstrack(void)
|
||||
// Crosstrack Error
|
||||
// ----------------
|
||||
// If we are too far off or too close we don't do track following
|
||||
if (wp_totalDistance >= (unsigned)max(g.crosstrack_min_distance,0) &&
|
||||
if (wp_totalDistance >= (uint32_t)max(g.crosstrack_min_distance,0) &&
|
||||
abs(wrap_180_cd(target_bearing_cd - crosstrack_bearing_cd)) < 4500) {
|
||||
// Meters we are off track line
|
||||
crosstrack_error = sinf(radians((target_bearing_cd - crosstrack_bearing_cd) * 0.01)) * wp_distance;
|
||||
|
Loading…
Reference in New Issue
Block a user