mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
GCS_MAVLink: move send_attitude up to GCS_MAVLINK
This commit is contained in:
parent
22916fd97e
commit
514bc5c21d
@ -181,6 +181,7 @@ public:
|
|||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||||
void send_opticalflow(const OpticalFlow &optflow);
|
void send_opticalflow(const OpticalFlow &optflow);
|
||||||
#endif
|
#endif
|
||||||
|
virtual void send_attitude() const;
|
||||||
void send_autopilot_version() const;
|
void send_autopilot_version() const;
|
||||||
void send_local_position() const;
|
void send_local_position() const;
|
||||||
void send_vibration() const;
|
void send_vibration() const;
|
||||||
|
@ -2693,6 +2693,21 @@ bool GCS_MAVLINK::try_send_camera_message(const enum ap_message id)
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void GCS_MAVLINK::send_attitude() const
|
||||||
|
{
|
||||||
|
const AP_AHRS &ahrs = AP::ahrs();
|
||||||
|
const Vector3f omega = ahrs.get_gyro();
|
||||||
|
mavlink_msg_attitude_send(
|
||||||
|
chan,
|
||||||
|
AP_HAL::millis(),
|
||||||
|
ahrs.roll,
|
||||||
|
ahrs.pitch,
|
||||||
|
ahrs.yaw,
|
||||||
|
omega.x,
|
||||||
|
omega.y,
|
||||||
|
omega.z);
|
||||||
|
}
|
||||||
|
|
||||||
bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||||
{
|
{
|
||||||
if (telemetry_delayed()) {
|
if (telemetry_delayed()) {
|
||||||
@ -2703,6 +2718,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||||||
|
|
||||||
switch(id) {
|
switch(id) {
|
||||||
|
|
||||||
|
case MSG_ATTITUDE:
|
||||||
|
CHECK_PAYLOAD_SIZE(ATTITUDE);
|
||||||
|
send_attitude();
|
||||||
|
break;
|
||||||
|
|
||||||
case MSG_NEXT_PARAM:
|
case MSG_NEXT_PARAM:
|
||||||
CHECK_PAYLOAD_SIZE(PARAM_VALUE);
|
CHECK_PAYLOAD_SIZE(PARAM_VALUE);
|
||||||
queued_param_send();
|
queued_param_send();
|
||||||
|
Loading…
Reference in New Issue
Block a user