mirror of https://github.com/ArduPilot/ardupilot
Copter: fixed some uses of constrain_float() to be right type
This commit is contained in:
parent
9584aa89d9
commit
105bd32a2e
|
@ -68,7 +68,7 @@ static struct Location get_cmd_with_index(int i)
|
|||
static void set_cmd_with_index(struct Location temp, int i)
|
||||
{
|
||||
|
||||
i = constrain_float(i, 0, g.command_total.get());
|
||||
i = constrain_int16(i, 0, g.command_total.get());
|
||||
//cliSerial->printf("set_command: %d with id: %d\n", i, temp.id);
|
||||
|
||||
// store home as 0 altitude!!!
|
||||
|
|
|
@ -658,7 +658,7 @@ static void do_yaw()
|
|||
yaw_look_at_heading_slew = AUTO_YAW_SLEW_RATE;
|
||||
}else{
|
||||
int32_t turn_rate = (wrap_180_cd(yaw_look_at_heading - nav_yaw) / 100) / command_cond_queue.lat;
|
||||
yaw_look_at_heading_slew = constrain_float(turn_rate, 1, 360); // deg / sec
|
||||
yaw_look_at_heading_slew = constrain_int32(turn_rate, 1, 360); // deg / sec
|
||||
}
|
||||
|
||||
// set yaw mode
|
||||
|
|
Loading…
Reference in New Issue