mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 06:36:45 +08:00
mavlink streams: LORA mode for low bandwidth radio links (#24328)
Build all targets / Scan for Board Targets (push) Waiting to run
Build all targets / Build Group [${{ matrix.group }}] (push) Blocked by required conditions
Build all targets / Upload Artifacts to S3 (push) Blocked by required conditions
Build all targets / Create Release and Upload Artifacts (push) Blocked by required conditions
Checks / build (NO_NINJA_BUILD=1 px4_fmu-v5_default) (push) Waiting to run
Checks / build (NO_NINJA_BUILD=1 px4_sitl_default) (push) Waiting to run
Checks / build (check_format) (push) Waiting to run
Checks / build (check_newlines) (push) Waiting to run
Checks / build (module_documentation) (push) Waiting to run
Checks / build (px4_fmu-v2_default stack_check) (push) Waiting to run
Checks / build (px4_sitl_allyes) (push) Waiting to run
Checks / build (shellcheck_all) (push) Waiting to run
Checks / build (tests) (push) Waiting to run
Checks / build (tests_coverage) (push) Waiting to run
Checks / build (validate_module_configs) (push) Waiting to run
Clang Tidy / build (push) Waiting to run
MacOS build / build (px4_fmu-v5_default) (push) Waiting to run
MacOS build / build (px4_sitl) (push) Waiting to run
Ubuntu environment build / Build and Test (ubuntu:22.04) (push) Waiting to run
Ubuntu environment build / Build and Test (ubuntu:24.04) (push) Waiting to run
Container build / Build and Push Container (push) Waiting to run
EKF Update Change Indicator / unit_tests (push) Waiting to run
Failsafe Simulator Build / build (failsafe_web) (push) Waiting to run
FLASH usage analysis / Analyzing px4_fmu-v5x (push) Waiting to run
FLASH usage analysis / Analyzing px4_fmu-v6x (push) Waiting to run
MAVROS Mission Tests / build (map[mission:MC_mission_box vehicle:iris]) (push) Waiting to run
MAVROS Mission Tests / build (map[mission:rover_mission_1 vehicle:rover]) (push) Waiting to run
MAVROS Offboard Tests / build (map[test_file:mavros_posix_tests_offboard_posctl.test vehicle:iris]) (push) Waiting to run
Nuttx Target with extra env config / build (px4_fmu-v5_default) (push) Waiting to run
Python CI Checks / build (push) Waiting to run
ROS Translation Node Tests / Build and test (map[ros_version:humble ubuntu:jammy]) (push) Waiting to run
ROS Translation Node Tests / Build and test (map[ros_version:jazzy ubuntu:noble]) (push) Waiting to run
SITL Tests / Testing PX4 tailsitter (push) Waiting to run
SITL Tests / Testing PX4 iris (push) Waiting to run
SITL Tests / Testing PX4 standard_vtol (push) Waiting to run
Build all targets / Scan for Board Targets (push) Waiting to run
Build all targets / Build Group [${{ matrix.group }}] (push) Blocked by required conditions
Build all targets / Upload Artifacts to S3 (push) Blocked by required conditions
Build all targets / Create Release and Upload Artifacts (push) Blocked by required conditions
Checks / build (NO_NINJA_BUILD=1 px4_fmu-v5_default) (push) Waiting to run
Checks / build (NO_NINJA_BUILD=1 px4_sitl_default) (push) Waiting to run
Checks / build (check_format) (push) Waiting to run
Checks / build (check_newlines) (push) Waiting to run
Checks / build (module_documentation) (push) Waiting to run
Checks / build (px4_fmu-v2_default stack_check) (push) Waiting to run
Checks / build (px4_sitl_allyes) (push) Waiting to run
Checks / build (shellcheck_all) (push) Waiting to run
Checks / build (tests) (push) Waiting to run
Checks / build (tests_coverage) (push) Waiting to run
Checks / build (validate_module_configs) (push) Waiting to run
Clang Tidy / build (push) Waiting to run
MacOS build / build (px4_fmu-v5_default) (push) Waiting to run
MacOS build / build (px4_sitl) (push) Waiting to run
Ubuntu environment build / Build and Test (ubuntu:22.04) (push) Waiting to run
Ubuntu environment build / Build and Test (ubuntu:24.04) (push) Waiting to run
Container build / Build and Push Container (push) Waiting to run
EKF Update Change Indicator / unit_tests (push) Waiting to run
Failsafe Simulator Build / build (failsafe_web) (push) Waiting to run
FLASH usage analysis / Analyzing px4_fmu-v5x (push) Waiting to run
FLASH usage analysis / Analyzing px4_fmu-v6x (push) Waiting to run
MAVROS Mission Tests / build (map[mission:MC_mission_box vehicle:iris]) (push) Waiting to run
MAVROS Mission Tests / build (map[mission:rover_mission_1 vehicle:rover]) (push) Waiting to run
MAVROS Offboard Tests / build (map[test_file:mavros_posix_tests_offboard_posctl.test vehicle:iris]) (push) Waiting to run
Nuttx Target with extra env config / build (px4_fmu-v5_default) (push) Waiting to run
Python CI Checks / build (push) Waiting to run
ROS Translation Node Tests / Build and test (map[ros_version:humble ubuntu:jammy]) (push) Waiting to run
ROS Translation Node Tests / Build and test (map[ros_version:jazzy ubuntu:noble]) (push) Waiting to run
SITL Tests / Testing PX4 tailsitter (push) Waiting to run
SITL Tests / Testing PX4 iris (push) Waiting to run
SITL Tests / Testing PX4 standard_vtol (push) Waiting to run
* Add LORA radiolink Mavlink message rates * Do not forward ONBOARD_COMPUTER_STATUS when using low bandwidth radio links * Update src/modules/mavlink/mavlink_main.cpp * Update src/modules/mavlink/mavlink_main.cpp * Update src/modules/mavlink/mavlink_main.cpp * Update src/modules/mavlink/mavlink_main.h * Update src/modules/mavlink/mavlink_main.h * Update src/modules/mavlink/module.yaml * Update src/modules/mavlink/mavlink_main.h --------- Co-authored-by: Sebastien <sebastien.courroux@auterion.com> Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
This commit is contained in:
@@ -481,6 +481,10 @@ Mavlink::forward_message(const mavlink_message_t *msg, Mavlink *self)
|
||||
return;
|
||||
}
|
||||
|
||||
if (self->get_mode() == MAVLINK_MODE_LOW_BANDWIDTH && msg->msgid == MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS) {
|
||||
return;
|
||||
}
|
||||
|
||||
LockGuard lg{mavlink_module_mutex};
|
||||
|
||||
for (Mavlink *inst : mavlink_module_instances) {
|
||||
@@ -1800,6 +1804,53 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
||||
#endif // !CONSTRAINED_FLASH
|
||||
break;
|
||||
|
||||
case MAVLINK_MODE_LOW_BANDWIDTH:
|
||||
// Note: streams requiring low latency come first
|
||||
configure_stream_local("TIMESYNC", 10.0f);
|
||||
configure_stream_local("CAMERA_TRIGGER", 2.0f);
|
||||
configure_stream_local("LOCAL_POSITION_NED", 1.0f);
|
||||
configure_stream_local("ATTITUDE", 1.0f);
|
||||
configure_stream_local("ALTITUDE", 1.0f);
|
||||
configure_stream_local("DISTANCE_SENSOR", 2.0f);
|
||||
configure_stream_local("MOUNT_ORIENTATION", 2.0f);
|
||||
configure_stream_local("OBSTACLE_DISTANCE", 2.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", 2.0f);
|
||||
configure_stream_local("ESC_INFO", 1.0f);
|
||||
configure_stream_local("ESC_STATUS", 2.0f);
|
||||
|
||||
configure_stream_local("ADSB_VEHICLE", 2.0f);
|
||||
configure_stream_local("ATTITUDE_TARGET", 0.5f);
|
||||
configure_stream_local("AVAILABLE_MODES", 0.3f);
|
||||
configure_stream_local("BATTERY_STATUS", 0.5f);
|
||||
configure_stream_local("CAMERA_IMAGE_CAPTURED", 2.0f);
|
||||
configure_stream_local("COLLISION", 2.0f);
|
||||
configure_stream_local("CURRENT_MODE", 0.5f);
|
||||
configure_stream_local("ESTIMATOR_STATUS", 1.0f);
|
||||
configure_stream_local("EXTENDED_SYS_STATE", 0.5f);
|
||||
configure_stream_local("GLOBAL_POSITION_INT", 1.0f);
|
||||
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
|
||||
configure_stream_local("GPS2_RAW", 2.0f);
|
||||
configure_stream_local("GPS_RAW_INT", 2.0f);
|
||||
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", 2.0f);
|
||||
configure_stream_local("PING", 0.1f);
|
||||
configure_stream_local("POSITION_TARGET_GLOBAL_INT", 1.0f);
|
||||
configure_stream_local("POSITION_TARGET_LOCAL_NED", 1.0f);
|
||||
configure_stream_local("RC_CHANNELS", 5.0f);
|
||||
configure_stream_local("SERVO_OUTPUT_RAW_0", 1.0f);
|
||||
configure_stream_local("SYS_STATUS", 0.5f);
|
||||
configure_stream_local("SYSTEM_TIME", 2.0f);
|
||||
configure_stream_local("TIME_ESTIMATE_TO_TARGET", 0.5f);
|
||||
configure_stream_local("TRAJECTORY_REPRESENTATION_WAYPOINTS", 2.0f);
|
||||
configure_stream_local("VFR_HUD", 1.0f);
|
||||
configure_stream_local("VIBRATION", 0.1f);
|
||||
configure_stream_local("WIND_COV", 0.1f);
|
||||
break;
|
||||
|
||||
case MAVLINK_MODE_UAVIONIX:
|
||||
configure_stream_local("UAVIONIX_ADSB_OUT_CFG", 0.1f);
|
||||
configure_stream_local("UAVIONIX_ADSB_OUT_DYNAMIC", 5.0f);
|
||||
|
||||
@@ -212,6 +212,7 @@ public:
|
||||
MAVLINK_MODE_GIMBAL,
|
||||
MAVLINK_MODE_ONBOARD_LOW_BANDWIDTH,
|
||||
MAVLINK_MODE_UAVIONIX,
|
||||
MAVLINK_MODE_LOW_BANDWIDTH,
|
||||
MAVLINK_MODE_COUNT
|
||||
};
|
||||
|
||||
@@ -266,6 +267,9 @@ public:
|
||||
case MAVLINK_MODE_ONBOARD_LOW_BANDWIDTH:
|
||||
return "OnboardLowBandwidth";
|
||||
|
||||
case MAVLINK_MODE_LOW_BANDWIDTH:
|
||||
return "Low Bandwidth";
|
||||
|
||||
case MAVLINK_MODE_UAVIONIX:
|
||||
return "uAvionix";
|
||||
|
||||
|
||||
@@ -73,6 +73,7 @@ parameters:
|
||||
10: Gimbal
|
||||
11: Onboard Low Bandwidth
|
||||
12: uAvionix
|
||||
13: Low Bandwidth
|
||||
reboot_required: true
|
||||
num_instances: *max_num_config_instances
|
||||
default: [0, 2, 0]
|
||||
|
||||
Reference in New Issue
Block a user