mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Rover: use new constrain_int16 function
This commit is contained in:
parent
a072afa223
commit
be39ccf02c
@ -28,7 +28,7 @@ static void throttle_slew_limit(int16_t last_throttle)
|
||||
if (temp < 1) {
|
||||
temp = 1;
|
||||
}
|
||||
g.channel_throttle.radio_out = constrain(g.channel_throttle.radio_out, last_throttle - temp, last_throttle + temp);
|
||||
g.channel_throttle.radio_out = constrain_int16(g.channel_throttle.radio_out, last_throttle - temp, last_throttle + temp);
|
||||
}
|
||||
}
|
||||
|
||||
@ -45,7 +45,7 @@ static void calc_throttle()
|
||||
groundspeed_error = rov_speed - (float)ground_speed;
|
||||
|
||||
throttle = throttle_target + g.pidTeThrottle.get_pid(groundspeed_error);
|
||||
g.channel_throttle.servo_out = constrain(throttle, 0, g.throttle_max.get());
|
||||
g.channel_throttle.servo_out = constrain_int16(throttle, 0, g.throttle_max.get());
|
||||
}
|
||||
|
||||
/*****************************************
|
||||
@ -70,7 +70,7 @@ static void calc_nav_roll()
|
||||
nav_roll += 9000; // if obstacle in front turn 90° right
|
||||
speed_boost = false;
|
||||
}
|
||||
nav_roll = constrain(nav_roll, -g.roll_limit.get(), g.roll_limit.get());
|
||||
nav_roll = constrain_int16(nav_roll, -g.roll_limit.get(), g.roll_limit.get());
|
||||
}
|
||||
|
||||
// Zeros out navigation Integrators if we are changing mode, have passed a waypoint, etc.
|
||||
@ -105,7 +105,7 @@ static void set_servos(void)
|
||||
g.channel_rudder.calc_pwm();
|
||||
|
||||
g.channel_throttle.radio_out = g.channel_throttle.radio_in;
|
||||
g.channel_throttle.servo_out = constrain(g.channel_throttle.servo_out, g.throttle_min.get(), g.throttle_max.get());
|
||||
g.channel_throttle.servo_out = constrain_int16(g.channel_throttle.servo_out, g.throttle_min.get(), g.throttle_max.get());
|
||||
}
|
||||
|
||||
if (control_mode >= AUTO) {
|
||||
|
@ -67,7 +67,7 @@ static struct Location get_cmd_with_index(int i)
|
||||
// -------
|
||||
static void set_cmd_with_index(struct Location temp, int i)
|
||||
{
|
||||
i = constrain(i, 0, g.command_total.get());
|
||||
i = constrain_int16(i, 0, g.command_total.get());
|
||||
uint16_t mem = WP_START_BYTE + (i * WP_SIZE);
|
||||
|
||||
// Set altitude options bitmask
|
||||
|
@ -76,7 +76,7 @@ static void read_trim_switch()
|
||||
} else if (control_mode == LEARNING) {
|
||||
// if SW7 is ON in LEARNING = record the Wp
|
||||
// set the next_WP (home is stored at 0)
|
||||
CH7_wp_index = constrain(CH7_wp_index, 1, MAX_WAYPOINTS);
|
||||
CH7_wp_index = constrain_int16(CH7_wp_index, 1, MAX_WAYPOINTS);
|
||||
|
||||
current_loc.id = MAV_CMD_NAV_WAYPOINT;
|
||||
|
||||
|
@ -155,7 +155,7 @@ test_radio(uint8_t argc, const Menu::arg *argv)
|
||||
// ------------------------------
|
||||
set_servos();
|
||||
|
||||
tuning_value = constrain(((float)(g.rc_7.radio_in - g.rc_7.radio_min) / (float)(g.rc_7.radio_max - g.rc_7.radio_min)),0,1);
|
||||
tuning_value = constrain(((float)(g.rc_7.radio_in - g.rc_7.radio_min) / (float)(g.rc_7.radio_max - g.rc_7.radio_min)),0,1);
|
||||
|
||||
cliSerial->printf_P(PSTR("IN 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d Tuning = %2.3f\n"),
|
||||
g.channel_roll.control_in,
|
||||
|
Loading…
Reference in New Issue
Block a user