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

Log attitude information at full resolution #28008

Merged
merged 6 commits into from
Sep 10, 2024
Merged
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
4 changes: 1 addition & 3 deletions AntennaTracker/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,7 @@
// Write an attitude packet
void Tracker::Log_Write_Attitude()
{
Vector3f targets;
targets.y = nav_status.pitch * 100.0f;
targets.z = wrap_360_cd(nav_status.bearing * 100.0f);
const Vector3f targets{0.0f, nav_status.pitch, nav_status.bearing};
ahrs.Write_Attitude(targets);
AP::ahrs().Log_Write();
}
Expand Down
4 changes: 1 addition & 3 deletions ArduCopter/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,9 +75,7 @@ void Copter::Log_Write_Control_Tuning()
// Write an attitude packet
void Copter::Log_Write_Attitude()
{
Vector3f targets = attitude_control->get_att_target_euler_cd();
targets.z = wrap_360_cd(targets.z);
ahrs.Write_Attitude(targets);
ahrs.Write_Attitude(attitude_control->get_att_target_euler_rad() * RAD_TO_DEG);
ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control);
}

Expand Down
12 changes: 6 additions & 6 deletions ArduPlane/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,11 @@
// Write an attitude packet
void Plane::Log_Write_Attitude(void)
{
Vector3f targets; // Package up the targets into a vector for commonality with Copter usage of Log_Wrote_Attitude
targets.x = nav_roll_cd;
targets.y = nav_pitch_cd;
targets.z = 0; //Plane does not have the concept of navyaw. This is a placeholder.
Vector3f targets { // Package up the targets into a vector for commonality with Copter usage of Log_Wrote_Attitude
nav_roll_cd * 0.01f,
nav_pitch_cd * 0.01f,
0 //Plane does not have the concept of navyaw. This is a placeholder.
};

#if HAL_QUADPLANE_ENABLED
if (quadplane.show_vtol_view()) {
Expand All @@ -18,8 +19,7 @@ void Plane::Log_Write_Attitude(void)
// since Euler angles are not used and it is a waste of cpu to compute them at the loop rate.
// Get them from the quaternion instead:
quadplane.attitude_control->get_attitude_target_quat().to_euler(targets.x, targets.y, targets.z);
targets *= degrees(100.0f);
quadplane.ahrs_view->Write_AttitudeView(targets);
quadplane.ahrs_view->Write_AttitudeView(targets * RAD_TO_DEG);
} else
#endif
{
Expand Down
4 changes: 1 addition & 3 deletions ArduSub/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,9 +59,7 @@ void Sub::Log_Write_Control_Tuning()
// Write an attitude packet
void Sub::Log_Write_Attitude()
{
Vector3f targets = attitude_control.get_att_target_euler_cd();
targets.z = wrap_360_cd(targets.z);
ahrs.Write_Attitude(targets);
ahrs.Write_Attitude(attitude_control.get_att_target_euler_rad() * RAD_TO_DEG);

AP::ahrs().Log_Write();
}
Expand Down
4 changes: 2 additions & 2 deletions Rover/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
// Write an attitude packet
void Rover::Log_Write_Attitude()
{
float desired_pitch_cd = degrees(g2.attitude_control.get_desired_pitch()) * 100.0f;
const Vector3f targets(0.0f, desired_pitch_cd, 0.0f);
float desired_pitch = degrees(g2.attitude_control.get_desired_pitch());
andyp1per marked this conversation as resolved.
Show resolved Hide resolved
const Vector3f targets(0.0f, desired_pitch, 0.0f);

ahrs.Write_Attitude(targets);

Expand Down
28 changes: 14 additions & 14 deletions libraries/AP_AHRS/AP_AHRS_Logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,18 +48,18 @@ void AP_AHRS::Write_AOA_SSA(void) const
AP::logger().WriteBlock(&aoa_ssa, sizeof(aoa_ssa));
}

// Write an attitude packet
// Write an attitude packet, targets in degrees
void AP_AHRS::Write_Attitude(const Vector3f &targets) const
{
const struct log_Attitude pkt{
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
time_us : AP_HAL::micros64(),
control_roll : (int16_t)targets.x,
roll : (int16_t)roll_sensor,
control_pitch : (int16_t)targets.y,
pitch : (int16_t)pitch_sensor,
control_yaw : (uint16_t)wrap_360_cd(targets.z),
yaw : (uint16_t)wrap_360_cd(yaw_sensor),
control_roll : targets.x,
roll : degrees(roll),
control_pitch : targets.y,
pitch : degrees(pitch),
control_yaw : wrap_360(targets.z),
yaw : wrap_360(degrees(yaw)),
active : uint8_t(active_EKF_type()),
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
Expand Down Expand Up @@ -122,18 +122,18 @@ void AP_AHRS::write_video_stabilisation() const
AP::logger().WriteBlock(&pkt, sizeof(pkt));
}

// Write an attitude view packet
// Write an attitude view packet, targets in degrees
void AP_AHRS_View::Write_AttitudeView(const Vector3f &targets) const
{
const struct log_Attitude pkt{
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
time_us : AP_HAL::micros64(),
control_roll : (int16_t)targets.x,
roll : (int16_t)roll_sensor,
control_pitch : (int16_t)targets.y,
pitch : (int16_t)pitch_sensor,
control_yaw : (uint16_t)wrap_360_cd(targets.z),
yaw : (uint16_t)wrap_360_cd(yaw_sensor),
control_roll : targets.x,
roll : degrees(roll),
control_pitch : targets.y,
pitch : degrees(pitch),
control_yaw : wrap_360(targets.z),
yaw : wrap_360(degrees(yaw)),
active : uint8_t(AP::ahrs().active_EKF_type()),
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
Expand Down
14 changes: 7 additions & 7 deletions libraries/AP_AHRS/LogStructure.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,12 +61,12 @@ struct PACKED log_AOA_SSA {
struct PACKED log_Attitude {
LOG_PACKET_HEADER;
uint64_t time_us;
int16_t control_roll;
int16_t roll;
int16_t control_pitch;
int16_t pitch;
uint16_t control_yaw;
uint16_t yaw;
float control_roll;
float roll;
float control_pitch;
float pitch;
float control_yaw;
float yaw;
uint8_t active;
};

Expand Down Expand Up @@ -195,7 +195,7 @@ struct PACKED log_ATSC {
{ LOG_AOA_SSA_MSG, sizeof(log_AOA_SSA), \
"AOA", "Qff", "TimeUS,AOA,SSA", "sdd", "F00" , true }, \
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),\
"ATT", "QccccCCB", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,AEKF", "sddddhh-", "FBBBBBB-" , true }, \
"ATT", "QffffffB", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,AEKF", "sddddhh-", "F000000-" , true }, \
{ LOG_ORGN_MSG, sizeof(log_ORGN), \
"ORGN","QBLLe","TimeUS,Type,Lat,Lng,Alt", "s#DUm", "F-GGB" }, \
{ LOG_POS_MSG, sizeof(log_POS), \
Expand Down
Loading