Skip to content

Commit 994550e

Browse files
committed
Pass mavlink_message_t into handle_decoded_message for heartbeat
This may become the pattern in the future for all messages.
1 parent c96aaf8 commit 994550e

6 files changed

+16
-12
lines changed

analyzing_mavlink_message_handler.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -198,7 +198,7 @@ void Analyzing_MAVLink_Message_Handler::handle_decoded_message(uint64_t T, mavli
198198
_analyze->evaluate_all();
199199
}
200200

201-
void Analyzing_MAVLink_Message_Handler::handle_decoded_message(uint64_t T, mavlink_heartbeat_t &msg) {
201+
void Analyzing_MAVLink_Message_Handler::handle_decoded_message(uint64_t T, mavlink_message_t &m UNUSED, mavlink_heartbeat_t &msg) {
202202
_vehicle->set_T(T);
203203

204204
if (msg.autopilot == 8) {

analyzing_mavlink_message_handler.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ class Analyzing_MAVLink_Message_Handler : public MAVLink_Message_Handler {
3636
virtual void handle_decoded_message(uint64_t T, mavlink_ekf_status_report_t &msg) override;
3737
virtual void handle_decoded_message(uint64_t T, mavlink_gps_raw_int_t &msg) override;
3838
virtual void handle_decoded_message(uint64_t T, mavlink_global_position_int_t &msg) override;
39-
virtual void handle_decoded_message(uint64_t T, mavlink_heartbeat_t &msg) override;
39+
virtual void handle_decoded_message(uint64_t T, mavlink_message_t &m UNUSED, mavlink_heartbeat_t &msg) override;
4040
virtual void handle_decoded_message(uint64_t T, mavlink_nav_controller_output_t &msg) override;
4141
virtual void handle_decoded_message(uint64_t T, mavlink_param_value_t &msg) override;
4242
virtual void handle_decoded_message(uint64_t T, mavlink_power_status_t &msg) override;

dataflash_logger.cpp

+9-6
Original file line numberDiff line numberDiff line change
@@ -247,15 +247,18 @@ void DataFlash_Logger::logging_stop()
247247
logging_started = false;
248248
}
249249

250-
void DataFlash_Logger::handle_message(uint64_t timestamp, mavlink_message_t &msg)
250+
void DataFlash_Logger::handle_decoded_message(uint64_t T,
251+
mavlink_message_t &m,
252+
mavlink_heartbeat_t &msg)
251253
{
252-
if (!logging_started && msg.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
253-
la_log(LOG_INFO, "Heartbeat received from %u/%u", msg.sysid, msg.compid);
254+
if (!logging_started) {
255+
la_log(LOG_INFO, "Heartbeat received from %u/%u", m.sysid, m.compid);
254256
}
255257

256-
most_recent_sender_system_id = msg.sysid;
257-
most_recent_sender_component_id = msg.compid;
258-
MAVLink_Message_Handler::handle_message(timestamp, msg);
258+
most_recent_sender_system_id = m.sysid;
259+
most_recent_sender_component_id = m.compid;
260+
261+
MAVLink_Message_Handler::handle_decoded_message(T, m, msg);
259262
}
260263

261264
void DataFlash_Logger::handle_decoded_message(uint64_t T UNUSED, mavlink_remote_log_data_block_t &msg)

dataflash_logger.h

+3-2
Original file line numberDiff line numberDiff line change
@@ -61,8 +61,9 @@ class DataFlash_Logger : public MAVLink_Message_Handler {
6161
int out_fd;
6262
bool logging_started = false;
6363

64-
65-
void handle_message(uint64_t timestamp, mavlink_message_t &msg);
64+
void handle_decoded_message(uint64_t T,
65+
mavlink_message_t &m,
66+
mavlink_heartbeat_t &msg);
6667
void handle_decoded_message(uint64_t T, mavlink_remote_log_data_block_t &msg);
6768

6869
bool make_new_log_filename(char *buffer, uint8_t bufferlen);

mavlink_message_handler.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ void MAVLink_Message_Handler::handle_message(uint64_t timestamp, mavlink_message
4343
case MAVLINK_MSG_ID_HEARTBEAT: {
4444
mavlink_heartbeat_t decoded;
4545
mavlink_msg_heartbeat_decode(&msg, &decoded);
46-
handle_decoded_message(timestamp, decoded);
46+
handle_decoded_message(timestamp, msg, decoded);
4747
break;
4848
}
4949
case MAVLINK_MSG_ID_MOUNT_STATUS: {

mavlink_message_handler.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ class MAVLink_Message_Handler : public Message_Handler {
4040
virtual void handle_decoded_message(uint64_t T UNUSED, mavlink_ekf_status_report_t &msg UNUSED) { }
4141
virtual void handle_decoded_message(uint64_t T UNUSED, mavlink_gps_raw_int_t &msg UNUSED) { }
4242
virtual void handle_decoded_message(uint64_t T UNUSED, mavlink_global_position_int_t &msg UNUSED) { }
43-
virtual void handle_decoded_message(uint64_t T UNUSED, mavlink_heartbeat_t &msg UNUSED) { }
43+
virtual void handle_decoded_message(uint64_t T UNUSED, mavlink_message_t &m UNUSED, mavlink_heartbeat_t &msg UNUSED) { }
4444
virtual void handle_decoded_message(uint64_t T UNUSED, mavlink_log_entry_t &msg UNUSED) { }
4545
virtual void handle_decoded_message(uint64_t T UNUSED, mavlink_log_data_t &msg UNUSED) { }
4646
virtual void handle_decoded_message(uint64_t T UNUSED, mavlink_mount_status_t &msg UNUSED) { }

0 commit comments

Comments
 (0)