mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 09:28:58 +00:00
Improvements for the iridiumsbd driver
- Update heartbeat after successful sbd session and fill it in the telemetry_status message - Add parameter for session timeout, read interval, and stacking time - Add sbd session timeout - Fix updating the rssi at a constant rate when no sbd session is scheduled - Add variable timout to read_at function - Check if test command is valid to avoid being stuck in the test state
This commit is contained in:
@@ -1979,8 +1979,10 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
|
||||
/* Activate sending the data by default except for the IRIDIUM mode */
|
||||
_transmitting_enabled = true;
|
||||
if (_mode == MAVLINK_MODE_IRIDIUM)
|
||||
|
||||
if (_mode == MAVLINK_MODE_IRIDIUM) {
|
||||
_transmitting_enabled = false;
|
||||
}
|
||||
|
||||
/* add default streams depending on mode */
|
||||
if (_mode != MAVLINK_MODE_IRIDIUM) {
|
||||
@@ -2196,14 +2198,18 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
struct vehicle_command_s vehicle_cmd;
|
||||
|
||||
if (cmd_sub->update(&cmd_time, &vehicle_cmd)) {
|
||||
if (vehicle_cmd.command == vehicle_command_s::VEHICLE_CMD_MAVLINK_ENABLE_SENDING) {
|
||||
if (_mode == (int)round(vehicle_cmd.param1)) {
|
||||
if (_transmitting_enabled != (int)vehicle_cmd.param2) {
|
||||
if ((int)vehicle_cmd.param2)
|
||||
if ((int)vehicle_cmd.param2) {
|
||||
PX4_INFO("Enable transmitting with mavlink instance of type %s on device %s", mavlink_mode_str(_mode), _device_name);
|
||||
else
|
||||
|
||||
} else {
|
||||
PX4_INFO("Disable transmitting with mavlink instance of type %s on device %s", mavlink_mode_str(_mode), _device_name);
|
||||
}
|
||||
|
||||
_transmitting_enabled = (int)vehicle_cmd.param2;
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user