Skip to content

Conversation

@tejalbarnwal
Copy link

Adds support for logging commanded yaw and yaw rates from the guided setpoint target.
The implementation uses get_heading() method of the AutoYaw object to get the yaw and yaw rate target.
I have tested the branch in SITL.
Please let me know your thoughts on the implementation.
@peterbarker , @rmackay9

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Commit message could be Copter: mode_guided: log yaw and yaw rate for SET_POSITION_TARGET_LOCAL_NED

Seems like a reasonable change - 'though I wonder why we weren't logging this before.... (@lthall )

accel_target_y : accel_target_mss.y,
accel_target_z : accel_target_mss.z
accel_target_z : accel_target_mss.z,
yaw_target : wrap_360(degrees(yaw_rad)),
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why the wrap_360?

Copy link
Author

@tejalbarnwal tejalbarnwal Oct 25, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hey,
I wrapped it to 360° since -π/2 was causing issues to compare with ATT.Yaw and ArduPilot logs yaw in [0, 360), so this makes it easier to compare with ATT.yaw.
Screenshot from 2025-10-23 18-21-00

@peterbarker let me know your thoughts

accel_target_z : accel_target_mss.z
accel_target_z : accel_target_mss.z,
yaw_target : wrap_360(degrees(yaw_rad)),
yaw_rate_target : yaw_rate_rads
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
yaw_rate_target : yaw_rate_rads
yaw_rate_target : yaw_rate_rads,

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I added the formatting changes to the code

// terrain should be 0 if pos_target_m.z is alt-above-ekf-origin, 1 if alt-above-terrain
// vel_target_ms is m/s
void Copter::Log_Write_Guided_Position_Target(ModeGuided::SubMode submode, const Vector3p& pos_target_m, bool is_terrain_alt, const Vector3f& vel_target_ms, const Vector3f& accel_target_mss)
void Copter::Log_Write_Guided_Position_Target(ModeGuided::SubMode submode, const Vector3p& pos_target_m, bool is_terrain_alt, const Vector3f& vel_target_ms, const Vector3f& accel_target_mss, const float yaw_rad, const float yaw_rate_rads)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
void Copter::Log_Write_Guided_Position_Target(ModeGuided::SubMode submode, const Vector3p& pos_target_m, bool is_terrain_alt, const Vector3f& vel_target_ms, const Vector3f& accel_target_mss, const float yaw_rad, const float yaw_rate_rads)
void Copter::Log_Write_Guided_Position_Target(ModeGuided::SubMode submode, const Vector3p& pos_target_m, bool is_terrain_alt, const Vector3f& vel_target_ms, const Vector3f& accel_target_mss, const float yaw_target_rad, const float yaw_target_rate_rads)

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I added the above renaming changes to the code

Comment on lines 469 to 470
AC_AttitudeControl::HeadingCommand yaw_command = auto_yaw.get_heading();
// log target
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
AC_AttitudeControl::HeadingCommand yaw_command = auto_yaw.get_heading();
// log target
// log target
AC_AttitudeControl::HeadingCommand yaw_command = auto_yaw.get_heading();

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Incorporated the order of comment updates to the code

@tejalbarnwal
Copy link
Author

tejalbarnwal commented Oct 25, 2025

Commit message could be Copter: mode_guided: log yaw and yaw rate for SET_POSITION_TARGET_LOCAL_NED

Seems like a reasonable change - 'though I wonder why we weren't logging this before.... (@lthall )

Hi @peterbarker ,
I updated the commit message and also added new commits related to all the formatting suggestions you gave and squashed them into one commit.

@tejalbarnwal tejalbarnwal force-pushed the yaw-logging-on-guided-pos-target branch from 2718a4e to c7da249 Compare October 25, 2025 12:28
…AL_NED

Adds support for logging commanded yaw in GUIDED pose targets.
Uses AutoYaw object get_heading() to get targets for yaw and yaw rates
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants