Skip to content

Commit 7f82f17

Browse files
authored
Merge pull request #2567 from mavlink/pr-revert-yaw
Revert "[PATCH] Fix goto_location sending radians instead of degrees"
2 parents b4d03cc + f80a64f commit 7f82f17

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

src/mavsdk/plugins/action/action_impl.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -477,7 +477,7 @@ void ActionImpl::goto_location_async(
477477
command.command = MAV_CMD_DO_REPOSITION;
478478
command.target_component_id = _system_impl->get_autopilot_id();
479479
command.frame = MAV_FRAME_GLOBAL_INT;
480-
command.params.maybe_param4 = yaw_deg;
480+
command.params.maybe_param4 = static_cast<float>(to_rad_from_deg(yaw_deg));
481481
command.params.x = int32_t(std::round(latitude_deg * 1e7));
482482
command.params.y = int32_t(std::round(longitude_deg * 1e7));
483483
command.params.maybe_z = altitude_amsl_m;

0 commit comments

Comments
 (0)