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

Copter: Guided Angle: Initialize yaw to current yaw. #26407

Merged
merged 1 commit into from
Mar 25, 2024
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
7 changes: 2 additions & 5 deletions ArduCopter/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -313,14 +313,11 @@ void ModeGuided::angle_control_start()

// initialise targets
guided_angle_state.update_time_ms = millis();
guided_angle_state.attitude_quat.initialise();
guided_angle_state.attitude_quat.from_euler(Vector3f(0.0, 0.0, attitude_control->get_att_target_euler_rad().z));
lthall marked this conversation as resolved.
Show resolved Hide resolved
guided_angle_state.ang_vel.zero();
guided_angle_state.climb_rate_cms = 0.0f;
guided_angle_state.yaw_rate_cds = 0.0f;
guided_angle_state.use_yaw_rate = false;

// pilot always controls yaw
auto_yaw.set_mode(AutoYaw::Mode::HOLD);
}

// set_destination - sets guided mode's target destination
Expand Down Expand Up @@ -939,7 +936,7 @@ void ModeGuided::angle_control_run()
// check for timeout - set lean angles and climb rate to zero if no updates received for 3 seconds
uint32_t tnow = millis();
if (tnow - guided_angle_state.update_time_ms > get_timeout_ms()) {
guided_angle_state.attitude_quat.initialise();
guided_angle_state.attitude_quat.from_euler(Vector3f(0.0, 0.0, attitude_control->get_att_target_euler_rad().z));
guided_angle_state.ang_vel.zero();
climb_rate_cms = 0.0f;
if (guided_angle_state.use_thrust) {
Expand Down
Loading