forked from Archive/PX4-Autopilot
mavlink: publish SYS_STATUS at constant rate, don't look at update() result
This commit is contained in:
parent
7397e05b70
commit
de3efc0975
|
@ -262,7 +262,7 @@ protected:
|
||||||
|
|
||||||
void send(const hrt_abstime t)
|
void send(const hrt_abstime t)
|
||||||
{
|
{
|
||||||
if (status_sub->update(t)) {
|
status_sub->update(t);
|
||||||
mavlink_msg_sys_status_send(_channel,
|
mavlink_msg_sys_status_send(_channel,
|
||||||
status->onboard_control_sensors_present,
|
status->onboard_control_sensors_present,
|
||||||
status->onboard_control_sensors_enabled,
|
status->onboard_control_sensors_enabled,
|
||||||
|
@ -278,7 +278,6 @@ protected:
|
||||||
status->errors_count3,
|
status->errors_count3,
|
||||||
status->errors_count4);
|
status->errors_count4);
|
||||||
}
|
}
|
||||||
}
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue