Skip to content

Commit

Permalink
mavlink: Add handling of esc_status message
Browse files Browse the repository at this point in the history
This is preparation for moving esc_status sending into gazebo mavlink plugin

Signed-off-by: Jukka Laitinen <[email protected]>
  • Loading branch information
jlaitine committed Aug 22, 2024
1 parent ff6cfdb commit e49cace
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 0 deletions.
27 changes: 27 additions & 0 deletions src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -317,6 +317,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_actuator_output_status(msg);
break;

case MAVLINK_MSG_ID_ESC_STATUS:
handle_message_esc_status(msg);
break;

default:
break;
}
Expand Down Expand Up @@ -3141,6 +3145,29 @@ MavlinkReceiver::handle_message_actuator_output_status(mavlink_message_t *msg)
}
}

void
MavlinkReceiver::handle_message_esc_status(mavlink_message_t *msg)
{
static constexpr int batch_size = MAVLINK_MSG_ESC_STATUS_FIELD_RPM_LEN;
mavlink_esc_status_t esc_status_msg;
mavlink_msg_esc_status_decode(msg, &esc_status_msg);
esc_status_s esc_status{};

esc_status.timestamp = hrt_absolute_time();

/* Status is sent in batches, esc_idx is the actual esc index, idx is the index within the received batch */

size_t esc_idx = esc_status_msg.index;

for (int idx = 0; idx < batch_size && esc_idx < sizeof(esc_status.esc) / sizeof(esc_status.esc[0]); idx++, esc_idx++) {
esc_status.esc[esc_idx].esc_rpm = esc_status_msg.rpm[idx];
esc_status.esc[esc_idx].esc_voltage = esc_status_msg.voltage[idx];
esc_status.esc[esc_idx].esc_current = esc_status_msg.current[idx];
}

_esc_status_pub.publish(esc_status);
}

void
MavlinkReceiver::run()
{
Expand Down
3 changes: 3 additions & 0 deletions src/modules/mavlink/mavlink_receiver.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@
#include <uORB/topics/collision_report.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/distance_sensor.h>
#include <uORB/topics/esc_status.h>
#include <uORB/topics/follow_target.h>
#include <uORB/topics/generator_status.h>
#include <uORB/topics/gimbal_manager_set_attitude.h>
Expand Down Expand Up @@ -204,6 +205,7 @@ class MavlinkReceiver : public ModuleParams
void handle_message_gimbal_device_information(mavlink_message_t *msg);
void handle_message_gimbal_device_attitude_status(mavlink_message_t *msg);
void handle_message_actuator_output_status(mavlink_message_t *msg);
void handle_message_esc_status(mavlink_message_t *msg);

#if !defined(CONSTRAINED_FLASH)
void handle_message_debug(mavlink_message_t *msg);
Expand Down Expand Up @@ -327,6 +329,7 @@ class MavlinkReceiver : public ModuleParams
uORB::Publication<vehicle_status_s> _redundant_status_pub[vehicle_status_s::MAX_REDUNDANT_CONTROLLERS] {ORB_ID(redundant_status0), ORB_ID(redundant_status1)};
vehicle_status_s _redundant_status[vehicle_status_s::MAX_REDUNDANT_CONTROLLERS] {};
uORB::Publication<actuator_outputs_s> _redundant_actuator_outputs_pub[vehicle_status_s::MAX_REDUNDANT_CONTROLLERS] {ORB_ID(redundant_actuator_outputs0), ORB_ID(redundant_actuator_outputs1)};
uORB::Publication<esc_status_s> _esc_status_pub{ORB_ID(esc_status)};

#if !defined(CONSTRAINED_FLASH)
uORB::Publication<debug_array_s> _debug_array_pub {ORB_ID(debug_array)};
Expand Down

0 comments on commit e49cace

Please sign in to comment.