voxl_esc: Added Mavlink tunnel UART pass-through mechanism
Some checks failed
Build all targets / Scan for Board Targets (push) Has been cancelled
Checks / build (NO_NINJA_BUILD=1 px4_fmu-v5_default) (push) Has been cancelled
Checks / build (NO_NINJA_BUILD=1 px4_sitl_default) (push) Has been cancelled
Checks / build (check_format) (push) Has been cancelled
Checks / build (check_newlines) (push) Has been cancelled
Checks / build (module_documentation) (push) Has been cancelled
Checks / build (px4_fmu-v2_default stack_check) (push) Has been cancelled
Checks / build (px4_sitl_allyes) (push) Has been cancelled
Checks / build (shellcheck_all) (push) Has been cancelled
Checks / build (tests) (push) Has been cancelled
Checks / build (tests_coverage) (push) Has been cancelled
Checks / build (validate_module_configs) (push) Has been cancelled
Clang Tidy / build (push) Has been cancelled
MacOS build / build (px4_fmu-v5_default) (push) Has been cancelled
MacOS build / build (px4_sitl) (push) Has been cancelled
Ubuntu environment build / Build and Test (ubuntu:22.04) (push) Has been cancelled
Ubuntu environment build / Build and Test (ubuntu:24.04) (push) Has been cancelled
Container build / Build and Push Container (push) Has been cancelled
EKF Update Change Indicator / unit_tests (push) Has been cancelled
Failsafe Simulator Build / build (failsafe_web) (push) Has been cancelled
FLASH usage analysis / Analyzing px4_fmu-v5x (push) Has been cancelled
FLASH usage analysis / Analyzing px4_fmu-v6x (push) Has been cancelled
MAVROS Mission Tests / build (map[mission:MC_mission_box vehicle:iris]) (push) Has been cancelled
MAVROS Mission Tests / build (map[mission:rover_mission_1 vehicle:rover]) (push) Has been cancelled
MAVROS Offboard Tests / build (map[test_file:mavros_posix_tests_offboard_posctl.test vehicle:iris]) (push) Has been cancelled
Nuttx Target with extra env config / build (px4_fmu-v5_default) (push) Has been cancelled
Python CI Checks / build (push) Has been cancelled
ROS Translation Node Tests / Build and test (map[ros_version:humble ubuntu:jammy]) (push) Has been cancelled
ROS Translation Node Tests / Build and test (map[ros_version:jazzy ubuntu:noble]) (push) Has been cancelled
SITL Tests / Testing PX4 tailsitter (push) Has been cancelled
SITL Tests / Testing PX4 iris (push) Has been cancelled
SITL Tests / Testing PX4 standard_vtol (push) Has been cancelled
Build all targets / Build Group [${{ matrix.group }}] (push) Has been cancelled
Build all targets / Upload Artifacts to S3 (push) Has been cancelled
Build all targets / Create Release and Upload Artifacts (push) Has been cancelled

This commit is contained in:
Eric Katzfey
2025-02-20 15:11:09 -08:00
committed by Daniel Agar
parent d4918ea118
commit 5fb810a5ea
5 changed files with 30 additions and 1 deletions

View File

@@ -18,3 +18,6 @@ uint8 target_system # System ID (can be 0 for broadcast, but this is discou
uint8 target_component # Component ID (can be 0 for broadcast, but this is discouraged)
uint8 payload_length # Length of the data transported in payload
uint8[128] payload # Data itself
# Topic aliases for known payload types
# TOPICS mavlink_tunnel esc_serial_passthru

View File

@@ -1334,6 +1334,20 @@ bool VoxlEsc::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
_esc_status_pub.publish(_esc_status);
uint8_t num_writes = 0;
while (_esc_serial_passthru_sub.updated() && (num_writes < 4)) {
mavlink_tunnel_s uart_passthru{};
_esc_serial_passthru_sub.copy(&uart_passthru);
if (_uart_port.write(uart_passthru.payload, uart_passthru.payload_length) != uart_passthru.payload_length) {
PX4_ERR("Failed to send mavlink tunnel data to esc");
return false;
}
num_writes++;
}
perf_count(_output_update_perf);
return true;

View File

@@ -49,6 +49,7 @@
#include <uORB/topics/led_control.h>
#include <uORB/topics/esc_status.h>
#include <uORB/topics/actuator_test.h>
#include <uORB/topics/mavlink_tunnel.h>
#include <px4_platform_common/Serial.hpp>
@@ -212,6 +213,7 @@ private:
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
uORB::Subscription _actuator_test_sub{ORB_ID(actuator_test)};
uORB::Subscription _led_update_sub{ORB_ID(led_control)};
uORB::Subscription _esc_serial_passthru_sub{ORB_ID(esc_serial_passthru)};
uORB::Publication<actuator_outputs_s> _outputs_debug_pub{ORB_ID(actuator_outputs_debug)};
uORB::Publication<esc_status_s> _esc_status_pub{ORB_ID(esc_status)};

View File

@@ -1976,7 +1976,16 @@ MavlinkReceiver::handle_message_tunnel(mavlink_message_t *msg)
memcpy(tunnel.payload, mavlink_tunnel.payload, sizeof(tunnel.payload));
static_assert(sizeof(tunnel.payload) == sizeof(mavlink_tunnel.payload), "mavlink_tunnel.payload size mismatch");
_mavlink_tunnel_pub.publish(tunnel);
switch (mavlink_tunnel.payload_type) {
case MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_ESC_UART_PASSTHRU:
_esc_serial_passthru_pub.publish(tunnel);
break;
default:
_mavlink_tunnel_pub.publish(tunnel);
break;
}
}

View File

@@ -307,6 +307,7 @@ private:
uORB::Publication<landing_target_pose_s> _landing_target_pose_pub{ORB_ID(landing_target_pose)};
uORB::Publication<log_message_s> _log_message_pub{ORB_ID(log_message)};
uORB::Publication<mavlink_tunnel_s> _mavlink_tunnel_pub{ORB_ID(mavlink_tunnel)};
uORB::Publication<mavlink_tunnel_s> _esc_serial_passthru_pub{ORB_ID(esc_serial_passthru)};
uORB::Publication<obstacle_distance_s> _obstacle_distance_pub{ORB_ID(obstacle_distance)};
uORB::Publication<offboard_control_mode_s> _offboard_control_mode_pub{ORB_ID(offboard_control_mode)};
uORB::Publication<onboard_computer_status_s> _onboard_computer_status_pub{ORB_ID(onboard_computer_status)};