Skip to content

Commit

Permalink
AP_Camera: camera-status-fov attitude in earth frame
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Dec 6, 2024
1 parent 84cb9d5 commit 6001ecc
Showing 1 changed file with 3 additions and 0 deletions.
3 changes: 3 additions & 0 deletions libraries/AP_Camera/AP_Camera_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -314,6 +314,9 @@ void AP_Camera_Backend::send_camera_fov_status(mavlink_channel_t chan) const
mount->get_attitude_quaternion(get_mount_instance(), quat);
}

// rotate attitude quaternion to earth frame using AHRS yaw
quat.rotate(Vector3f(0, 0, AP::ahrs().get_yaw()));

// send camera fov status message only if the last calculated values aren't stale
const float quat_array[4] = {
quat.q1,
Expand Down

0 comments on commit 6001ecc

Please sign in to comment.