v5x: use low bandwidth mavlink mode

This changes the default mavlink message set from onboard to
onboard_low_bandwidth, which drastically reduces the bandwidth required to get a
usable connection.
This commit is contained in:
Nico van Duijn 2021-02-17 10:37:41 +01:00 committed by Beat Küng
parent 846695f986
commit 8d3335906a
4 changed files with 57 additions and 1 deletions

View File

@ -6,7 +6,7 @@
if ver hwtypecmp V5Xa0 V5X91 V5Xa1
then
# Start MAVLink on the UART connected to the mission computer
mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard -x -z
mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z
else
# Start MAVLink on the USB port
mavlink start -d /dev/ttyACM0

View File

@ -1778,6 +1778,54 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
break;
case MAVLINK_MODE_ONBOARD_LOW_BANDWIDTH:
// Note: streams requiring low latency come first
configure_stream_local("TIMESYNC", 10.0f);
configure_stream_local("CAMERA_TRIGGER", unlimited_rate);
configure_stream_local("LOCAL_POSITION_NED", 30.0f);
configure_stream_local("ATTITUDE", 20.0f);
configure_stream_local("ALTITUDE", 10.0f);
configure_stream_local("DISTANCE_SENSOR", 10.0f);
configure_stream_local("MOUNT_ORIENTATION", 10.0f);
configure_stream_local("OBSTACLE_DISTANCE", 10.0f);
configure_stream_local("ODOMETRY", 30.0f);
configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 1.0f);
configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f);
configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f);
configure_stream_local("ADSB_VEHICLE", unlimited_rate);
configure_stream_local("ATTITUDE_TARGET", 2.0f);
configure_stream_local("BATTERY_STATUS", 0.5f);
configure_stream_local("COLLISION", unlimited_rate);
configure_stream_local("ESTIMATOR_STATUS", 1.0f);
configure_stream_local("EXTENDED_SYS_STATE", 1.0f);
configure_stream_local("GLOBAL_POSITION_INT", 10.0f);
configure_stream_local("GPS2_RAW", unlimited_rate);
configure_stream_local("GPS_RAW_INT", unlimited_rate);
configure_stream_local("HOME_POSITION", 0.5f);
configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.5f);
configure_stream_local("OPTICAL_FLOW_RAD", 1.0f);
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
configure_stream_local("PING", 0.1f);
configure_stream_local("POSITION_TARGET_GLOBAL_INT", 1.5f);
configure_stream_local("POSITION_TARGET_LOCAL_NED", 1.5f);
configure_stream_local("RC_CHANNELS", 5.0f);
configure_stream_local("SERVO_OUTPUT_RAW_0", 1.0f);
configure_stream_local("SYS_STATUS", 5.0f);
configure_stream_local("TRAJECTORY_REPRESENTATION_WAYPOINTS", 5.0f);
configure_stream_local("UTM_GLOBAL_POSITION", 1.0f);
configure_stream_local("VFR_HUD", 4.0f);
configure_stream_local("VIBRATION", 0.5f);
configure_stream_local("WIND_COV", 1.0f);
#if !defined(CONSTRAINED_FLASH)
configure_stream_local("DEBUG", 1.0f);
configure_stream_local("DEBUG_FLOAT_ARRAY", 1.0f);
configure_stream_local("DEBUG_VECT", 1.0f);
configure_stream_local("NAMED_VALUE_FLOAT", 1.0f);
#endif // !CONSTRAINED_FLASH
break;
default:
ret = -1;
break;
@ -1988,6 +2036,9 @@ Mavlink::task_main(int argc, char *argv[])
} else if (strcmp(myoptarg, "gimbal") == 0) {
_mode = MAVLINK_MODE_GIMBAL;
} else if (strcmp(myoptarg, "onboard_low_bandwidth") == 0) {
_mode = MAVLINK_MODE_ONBOARD_LOW_BANDWIDTH;
} else {
PX4_ERR("invalid mode");
err_flag = true;

View File

@ -192,6 +192,7 @@ public:
MAVLINK_MODE_EXTVISION,
MAVLINK_MODE_EXTVISIONMIN,
MAVLINK_MODE_GIMBAL,
MAVLINK_MODE_ONBOARD_LOW_BANDWIDTH,
MAVLINK_MODE_COUNT
};
@ -243,6 +244,9 @@ public:
case MAVLINK_MODE_GIMBAL:
return "Gimbal";
case MAVLINK_MODE_ONBOARD_LOW_BANDWIDTH:
return "OnboardLowBandwidth";
default:
return "Unknown";
}

View File

@ -59,6 +59,7 @@ parameters:
8: External Vision
#9: External Vision Minimal # hidden
10: Gimbal
11: Onboard Low Bandwidth
reboot_required: true
num_instances: *max_num_config_instances
default: [0, 2, 0]