Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added yaw to CMD_DO_SET_HOME #14810

Merged
merged 1 commit into from
Sep 11, 2021
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion src/modules/commander/Commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@
#include <math.h>
#include <float.h>
#include <cstring>
#include <matrix/math.hpp>

#include <uORB/topics/mavlink_log.h>

Expand Down Expand Up @@ -958,6 +959,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;
Expand All @@ -981,7 +984,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);
Expand Down