Copter: replace 4 divisions with multiplications

This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2019-04-23 19:26:30 +02:00 committed by Tom Pittenger
parent 295c343959
commit 402b1cba3f
2 changed files with 4 additions and 4 deletions

View File

@ -594,7 +594,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t
case MAV_CMD_DO_MOUNT_CONTROL: case MAV_CMD_DO_MOUNT_CONTROL:
if(!copter.camera_mount.has_pan_control()) { if(!copter.camera_mount.has_pan_control()) {
copter.flightmode->auto_yaw.set_fixed_yaw( copter.flightmode->auto_yaw.set_fixed_yaw(
(float)packet.param3 / 100.0f, (float)packet.param3 * 0.01f,
0.0f, 0.0f,
0,0); 0,0);
} }
@ -878,7 +878,7 @@ void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t* msg)
if(!copter.camera_mount.has_pan_control()) { if(!copter.camera_mount.has_pan_control()) {
// if the mount doesn't do pan control then yaw the entire vehicle instead: // if the mount doesn't do pan control then yaw the entire vehicle instead:
copter.flightmode->auto_yaw.set_fixed_yaw( copter.flightmode->auto_yaw.set_fixed_yaw(
mavlink_msg_mount_control_get_input_c(msg)/100.0f, mavlink_msg_mount_control_get_input_c(msg) * 0.01f,
0.0f, 0.0f,
0, 0,
0); 0);
@ -1337,7 +1337,7 @@ float GCS_MAVLINK_Copter::vfr_hud_alt() const
if (copter.g2.dev_options.get() & DevOptionVFR_HUDRelativeAlt) { if (copter.g2.dev_options.get() & DevOptionVFR_HUDRelativeAlt) {
// compatibility option for older mavlink-aware devices that // compatibility option for older mavlink-aware devices that
// assume Copter returns a relative altitude in VFR_HUD.alt // assume Copter returns a relative altitude in VFR_HUD.alt
return copter.current_loc.alt / 100.0f; return copter.current_loc.alt * 0.01f;
} }
return GCS_MAVLINK::vfr_hud_alt(); return GCS_MAVLINK::vfr_hud_alt();
} }

View File

@ -675,7 +675,7 @@ void Copter::ModeGuided::set_desired_velocity_with_accel_and_fence_limits(const
void Copter::ModeGuided::set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle) void Copter::ModeGuided::set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle)
{ {
if (use_yaw) { if (use_yaw) {
auto_yaw.set_fixed_yaw(yaw_cd / 100.0f, 0.0f, 0, relative_angle); auto_yaw.set_fixed_yaw(yaw_cd * 0.01f, 0.0f, 0, relative_angle);
} else if (use_yaw_rate) { } else if (use_yaw_rate) {
auto_yaw.set_rate(yaw_rate_cds); auto_yaw.set_rate(yaw_rate_cds);
} }