Plane: send attitude target message implementation (for quadplanes)

Minor modification -  implementation of the send_attitude_target msg. streaming (for quadplanes). The code is analogous in its structure and functionality to the implementation in Copter

Co-Authored-By: Peter Hall <33176108+IamPete1@users.noreply.github.com>
This commit is contained in:
Paweł Rozenblut 2023-10-13 10:40:09 +02:00 committed by Peter Barker
parent 030dfe2fa1
commit 1c6b4debe2
2 changed files with 31 additions and 0 deletions

View File

@ -157,6 +157,36 @@ void GCS_MAVLINK_Plane::send_attitude() const
omega.z);
}
void GCS_MAVLINK_Plane::send_attitude_target()
{
#if HAL_QUADPLANE_ENABLED
// Check if the attitude target is valid for reporting
const uint32_t now = AP_HAL::millis();
if (now - plane.quadplane.last_att_control_ms > 100) {
return;
}
const Quaternion quat = plane.quadplane.attitude_control->get_attitude_target_quat();
const Vector3f& ang_vel = plane.quadplane.attitude_control->get_attitude_target_ang_vel();
const float throttle = plane.quadplane.attitude_control->get_throttle_in();
const float quat_out[4] {quat.q1, quat.q2, quat.q3, quat.q4};
const uint16_t typemask = 0;
mavlink_msg_attitude_target_send(
chan,
now, // time since boot (ms)
typemask, // Bitmask that tells the system what control dimensions should be ignored by the vehicle
quat_out, // Target attitude quaternion [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], unit-length
ang_vel.x, // bodyframe target roll rate (rad/s)
ang_vel.y, // bodyframe target pitch rate (rad/s)
ang_vel.z, // bodyframe yaw rate (rad/s)
throttle); // Collective thrust, normalized to 0 .. 1
#endif // HAL_QUADPLANE_ENABLED
}
void GCS_MAVLINK_Plane::send_aoa_ssa()
{
AP_AHRS &ahrs = AP::ahrs();

View File

@ -32,6 +32,7 @@ protected:
void send_aoa_ssa();
void send_attitude() const override;
void send_attitude_target() override;
void send_wind() const;
bool persist_streamrates() const override { return true; }