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