Added yaw to CMD_DO_SET_HOME

This commit is contained in:
David Jablonski 2020-05-02 10:05:20 +02:00 committed by Daniel Agar
parent ce206d992b
commit 7d7200cf2f

View File

@ -74,6 +74,7 @@
#include <math.h>
#include <float.h>
#include <cstring>
#include <matrix/math.hpp>
#include <uORB/topics/mavlink_log.h>
@ -1030,6 +1031,8 @@ Commander::handle_command(const vehicle_command_s &cmd)
}
} else {
float yaw = matrix::wrap_2pi(math::radians(cmd.param4));
yaw = PX4_ISFINITE(yaw) ? yaw : NAN;
const double lat = cmd.param5;
const double lon = cmd.param6;
const float alt = cmd.param7;
@ -1053,7 +1056,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
float home_y;
map_projection_project(&ref_pos, lat, lon, &home_x, &home_y);
const float home_z = -(alt - local_pos.ref_alt);
fillLocalHomePos(home, home_x, home_y, home_z, 0.f);
fillLocalHomePos(home, home_x, home_y, home_z, yaw);
/* mark home position as set */
_status_flags.condition_home_position_valid = _home_pub.update(home);