AP_Logger: pass mavlink_message_t by const reference

This commit is contained in:
Pierre Kancir 2019-04-30 12:22:48 +02:00 committed by Peter Barker
parent 13ac187fd8
commit 781e9ae9c1
6 changed files with 29 additions and 29 deletions

View File

@ -651,9 +651,9 @@ bool AP_Logger::logging_started(void) {
return false;
}
void AP_Logger::handle_mavlink_msg(GCS_MAVLINK &link, mavlink_message_t* msg)
void AP_Logger::handle_mavlink_msg(GCS_MAVLINK &link, const mavlink_message_t &msg)
{
switch (msg->msgid) {
switch (msg.msgid) {
case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS:
FOR_EACH_BACKEND(remote_log_block_status_msg(link.get_chan(), msg));
break;

View File

@ -303,7 +303,7 @@ public:
void flush(void);
#endif
void handle_mavlink_msg(class GCS_MAVLINK &, mavlink_message_t* msg);
void handle_mavlink_msg(class GCS_MAVLINK &, const mavlink_message_t &msg);
void periodic_tasks(); // may want to split this into GCS/non-GCS duties
@ -501,12 +501,12 @@ private:
uint32_t _last_arming_failure_ms;
bool should_handle_log_message();
void handle_log_message(class GCS_MAVLINK &, mavlink_message_t *msg);
void handle_log_message(class GCS_MAVLINK &, const mavlink_message_t &msg);
void handle_log_request_list(class GCS_MAVLINK &, mavlink_message_t *msg);
void handle_log_request_data(class GCS_MAVLINK &, mavlink_message_t *msg);
void handle_log_request_erase(class GCS_MAVLINK &, mavlink_message_t *msg);
void handle_log_request_end(class GCS_MAVLINK &, mavlink_message_t *msg);
void handle_log_request_list(class GCS_MAVLINK &, const mavlink_message_t &msg);
void handle_log_request_data(class GCS_MAVLINK &, const mavlink_message_t &msg);
void handle_log_request_erase(class GCS_MAVLINK &, const mavlink_message_t &msg);
void handle_log_request_end(class GCS_MAVLINK &, const mavlink_message_t &msg);
void handle_log_send_listing(); // handle LISTING state
void handle_log_sending(); // handle SENDING state
bool handle_log_send_data(); // send data chunk to client

View File

@ -68,8 +68,8 @@ public:
#endif
// for Logger_MAVlink
virtual void remote_log_block_status_msg(mavlink_channel_t chan,
mavlink_message_t* msg) { }
virtual void remote_log_block_status_msg(const mavlink_channel_t chan,
const mavlink_message_t &msg) { }
// end for Logger_MAVlink
virtual void periodic_tasks();

View File

@ -222,8 +222,8 @@ void AP_Logger_MAVLink::stop_logging()
}
}
void AP_Logger_MAVLink::handle_ack(mavlink_channel_t chan,
mavlink_message_t* msg,
void AP_Logger_MAVLink::handle_ack(const mavlink_channel_t chan,
const mavlink_message_t &msg,
uint32_t seqno)
{
if (!_initialised) {
@ -245,8 +245,8 @@ void AP_Logger_MAVLink::handle_ack(mavlink_channel_t chan,
// }
stats_init();
_sending_to_client = true;
_target_system_id = msg->sysid;
_target_component_id = msg->compid;
_target_system_id = msg.sysid;
_target_component_id = msg.compid;
_chan = chan;
_next_seq_num = 0;
start_new_log_reset_variables();
@ -268,11 +268,11 @@ void AP_Logger_MAVLink::handle_ack(mavlink_channel_t chan,
}
}
void AP_Logger_MAVLink::remote_log_block_status_msg(mavlink_channel_t chan,
mavlink_message_t* msg)
void AP_Logger_MAVLink::remote_log_block_status_msg(const mavlink_channel_t chan,
const mavlink_message_t& msg)
{
mavlink_remote_log_block_status_t packet;
mavlink_msg_remote_log_block_status_decode(msg, &packet);
mavlink_msg_remote_log_block_status_decode(&msg, &packet);
if (!semaphore.take_nonblocking()) {
return;
}

View File

@ -61,7 +61,7 @@ public:
void push_log_blocks() override;
void remote_log_block_status_msg(mavlink_channel_t chan, mavlink_message_t* msg) override;
void remote_log_block_status_msg(const mavlink_channel_t chan, const mavlink_message_t& msg) override;
protected:
@ -76,7 +76,7 @@ private:
struct dm_block *next;
};
bool send_log_block(struct dm_block &block);
void handle_ack(mavlink_channel_t chan, mavlink_message_t* msg, uint32_t seqno);
void handle_ack(const mavlink_channel_t chan, const mavlink_message_t &msg, uint32_t seqno);
void handle_retry(uint32_t block_num);
void do_resends(uint32_t now);
void free_all_blocks();

View File

@ -40,12 +40,12 @@ bool AP_Logger::should_handle_log_message()
/**
handle all types of log download requests from the GCS
*/
void AP_Logger::handle_log_message(GCS_MAVLINK &link, mavlink_message_t *msg)
void AP_Logger::handle_log_message(GCS_MAVLINK &link, const mavlink_message_t &msg)
{
if (!should_handle_log_message()) {
return;
}
switch (msg->msgid) {
switch (msg.msgid) {
case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
handle_log_request_list(link, msg);
break;
@ -64,7 +64,7 @@ void AP_Logger::handle_log_message(GCS_MAVLINK &link, mavlink_message_t *msg)
/**
handle all types of log download requests from the GCS
*/
void AP_Logger::handle_log_request_list(GCS_MAVLINK &link, mavlink_message_t *msg)
void AP_Logger::handle_log_request_list(GCS_MAVLINK &link, const mavlink_message_t &msg)
{
WITH_SEMAPHORE(_log_send_sem);
@ -74,7 +74,7 @@ void AP_Logger::handle_log_request_list(GCS_MAVLINK &link, mavlink_message_t *ms
}
mavlink_log_request_list_t packet;
mavlink_msg_log_request_list_decode(msg, &packet);
mavlink_msg_log_request_list_decode(&msg, &packet);
_log_num_logs = get_num_logs();
if (_log_num_logs == 0) {
@ -102,7 +102,7 @@ void AP_Logger::handle_log_request_list(GCS_MAVLINK &link, mavlink_message_t *ms
/**
handle request for log data
*/
void AP_Logger::handle_log_request_data(GCS_MAVLINK &link, mavlink_message_t *msg)
void AP_Logger::handle_log_request_data(GCS_MAVLINK &link, const mavlink_message_t &msg)
{
WITH_SEMAPHORE(_log_send_sem);
@ -118,7 +118,7 @@ void AP_Logger::handle_log_request_data(GCS_MAVLINK &link, mavlink_message_t *ms
}
mavlink_log_request_data_t packet;
mavlink_msg_log_request_data_decode(msg, &packet);
mavlink_msg_log_request_data_decode(&msg, &packet);
// consider opening or switching logs:
if (transfer_activity != SENDING || _log_num_data != packet.id) {
@ -158,10 +158,10 @@ void AP_Logger::handle_log_request_data(GCS_MAVLINK &link, mavlink_message_t *ms
/**
handle request to erase log data
*/
void AP_Logger::handle_log_request_erase(GCS_MAVLINK &link, mavlink_message_t *msg)
void AP_Logger::handle_log_request_erase(GCS_MAVLINK &link, const mavlink_message_t &msg)
{
// mavlink_log_erase_t packet;
// mavlink_msg_log_erase_decode(msg, &packet);
// mavlink_msg_log_erase_decode(&msg, &packet);
EraseAll();
}
@ -169,11 +169,11 @@ void AP_Logger::handle_log_request_erase(GCS_MAVLINK &link, mavlink_message_t *m
/**
handle request to stop transfer and resume normal logging
*/
void AP_Logger::handle_log_request_end(GCS_MAVLINK &link, mavlink_message_t *msg)
void AP_Logger::handle_log_request_end(GCS_MAVLINK &link, const mavlink_message_t &msg)
{
WITH_SEMAPHORE(_log_send_sem);
mavlink_log_request_end_t packet;
mavlink_msg_log_request_end_decode(msg, &packet);
mavlink_msg_log_request_end_decode(&msg, &packet);
transfer_activity = IDLE;
_log_sending_link = nullptr;