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: Auto mode CONDITION_YAW treats neg relative angle with CCW direction as CCW #25646

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
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
8 changes: 6 additions & 2 deletions ArduCopter/autoyaw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,13 +110,17 @@ void Mode::AutoYaw::set_fixed_yaw(float angle_deg, float turn_rate_ds, int8_t di

// calculate final angle as relative to vehicle heading or absolute
if (relative_angle) {
// if both negative relative angle and CCW direction rotate in CCW direction
if (is_negative(angle_deg) && (direction < 0)) {
direction = 0;
}
_fixed_yaw_offset_cd = angle_deg * 100.0 * (direction >= 0 ? 1.0 : -1.0);
} else {
// absolute angle
_fixed_yaw_offset_cd = wrap_180_cd(angle_deg * 100.0 - _yaw_angle_cd);
if ( direction < 0 && is_positive(_fixed_yaw_offset_cd) ) {
if (direction < 0 && is_positive(_fixed_yaw_offset_cd)) {
_fixed_yaw_offset_cd -= 36000.0;
} else if ( direction > 0 && is_negative(_fixed_yaw_offset_cd) ) {
} else if (direction > 0 && is_negative(_fixed_yaw_offset_cd)) {
_fixed_yaw_offset_cd += 36000.0;
}
}
Expand Down
2 changes: 0 additions & 2 deletions ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1850,8 +1850,6 @@ void ModeAuto::do_yaw(const AP_Mission::Mission_Command& cmd)
// Do (Now) commands
/********************************************************************************/



void ModeAuto::do_change_speed(const AP_Mission::Mission_Command& cmd)
{
if (cmd.content.speed.target_ms > 0) {
Expand Down