Merge pull request #496 from PX4/wp_yaw_fix

missionlib: waypoint yaw fix
This commit is contained in:
Lorenz Meier 2013-10-30 11:26:58 -07:00
commit 9e74f178c9
1 changed files with 1 additions and 1 deletions

View File

@ -220,7 +220,7 @@ void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
sp.lon = param6_lon_y * 1e7f;
sp.altitude = param7_alt_z;
sp.altitude_is_relative = false;
sp.yaw = (param4 / 180.0f) * M_PI_F - M_PI_F;
sp.yaw = _wrap_pi(param4 / 180.0f * M_PI_F);
set_special_fields(param1, param2, param3, param4, command, &sp);
/* Initialize setpoint publication if necessary */