mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: use new functions
This commit is contained in:
parent
be39ccf02c
commit
06357c40f2
@ -1660,8 +1660,8 @@ void update_roll_pitch_mode(void)
|
||||
update_simple_mode();
|
||||
}
|
||||
// mix in user control with Nav control
|
||||
nav_roll += constrain(wrap_180(auto_roll - nav_roll), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second
|
||||
nav_pitch += constrain(wrap_180(auto_pitch - nav_pitch), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second
|
||||
nav_roll += constrain_int32(wrap_180(auto_roll - nav_roll), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second
|
||||
nav_pitch += constrain_int32(wrap_180(auto_pitch - nav_pitch), -g.auto_slew_rate.get(), g.auto_slew_rate.get()); // 40 deg a second
|
||||
|
||||
control_roll = g.rc_1.control_mix(nav_roll);
|
||||
control_pitch = g.rc_2.control_mix(nav_pitch);
|
||||
|
@ -473,7 +473,7 @@ test_ins(uint8_t argc, const Menu::arg *argv)
|
||||
accel = ins.get_accel();
|
||||
temp = ins.temperature();
|
||||
|
||||
float test = sqrt(sq(accel.x) + sq(accel.y) + sq(accel.z)) / 9.80665;
|
||||
float test = accel.length() / 9.80665;
|
||||
|
||||
cliSerial->printf_P(PSTR("a %7.4f %7.4f %7.4f g %7.4f %7.4f %7.4f t %74f | %7.4f\n"),
|
||||
accel.x, accel.y, accel.z,
|
||||
|
Loading…
Reference in New Issue
Block a user