AP_Mount: 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 781e9ae9c1
commit f3e40b4906
9 changed files with 28 additions and 28 deletions

View File

@ -598,28 +598,28 @@ MAV_RESULT AP_Mount::handle_command_long(const mavlink_command_long_t &packet)
}
/// Change the configuration of the mount
void AP_Mount::handle_mount_configure(const mavlink_message_t *msg)
void AP_Mount::handle_mount_configure(const mavlink_message_t &msg)
{
if (_primary >= AP_MOUNT_MAX_INSTANCES || _backends[_primary] == nullptr) {
return;
}
mavlink_mount_configure_t packet;
mavlink_msg_mount_configure_decode(msg, &packet);
mavlink_msg_mount_configure_decode(&msg, &packet);
// send message to backend
_backends[_primary]->handle_mount_configure(packet);
}
/// Control the mount (depends on the previously set mount configuration)
void AP_Mount::handle_mount_control(const mavlink_message_t *msg)
void AP_Mount::handle_mount_control(const mavlink_message_t &msg)
{
if (_primary >= AP_MOUNT_MAX_INSTANCES || _backends[_primary] == nullptr) {
return;
}
mavlink_mount_control_t packet;
mavlink_msg_mount_control_decode(msg, &packet);
mavlink_msg_mount_control_decode(&msg, &packet);
// send message to backend
_backends[_primary]->handle_mount_control(packet);
@ -646,7 +646,7 @@ void AP_Mount::set_roi_target(uint8_t instance, const struct Location &target_lo
}
// pass a GIMBAL_REPORT message to the backend
void AP_Mount::handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t *msg)
void AP_Mount::handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg)
{
for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
if (_backends[instance] != nullptr) {
@ -655,9 +655,9 @@ void AP_Mount::handle_gimbal_report(mavlink_channel_t chan, const mavlink_messag
}
}
void AP_Mount::handle_message(mavlink_channel_t chan, const mavlink_message_t *msg)
void AP_Mount::handle_message(mavlink_channel_t chan, const mavlink_message_t &msg)
{
switch (msg->msgid) {
switch (msg.msgid) {
case MAVLINK_MSG_ID_GIMBAL_REPORT:
handle_gimbal_report(chan, msg);
break;
@ -676,7 +676,7 @@ void AP_Mount::handle_message(mavlink_channel_t chan, const mavlink_message_t *m
}
// handle PARAM_VALUE
void AP_Mount::handle_param_value(const mavlink_message_t *msg)
void AP_Mount::handle_param_value(const mavlink_message_t &msg)
{
for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
if (_backends[instance] != nullptr) {

View File

@ -114,8 +114,8 @@ public:
// mavlink message handling:
MAV_RESULT handle_command_long(const mavlink_command_long_t &packet);
void handle_param_value(const mavlink_message_t *msg);
void handle_message(mavlink_channel_t chan, const mavlink_message_t *msg);
void handle_param_value(const mavlink_message_t &msg);
void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg);
// send a GIMBAL_REPORT message to GCS
void send_gimbal_report(mavlink_channel_t chan);
@ -175,9 +175,9 @@ protected:
private:
void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t *msg);
void handle_mount_configure(const mavlink_message_t *msg);
void handle_mount_control(const mavlink_message_t *msg);
void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg);
void handle_mount_configure(const mavlink_message_t &msg);
void handle_mount_control(const mavlink_message_t &msg);
MAV_RESULT handle_command_do_mount_configure(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_do_mount_control(const mavlink_command_long_t &packet);

View File

@ -70,10 +70,10 @@ public:
virtual void send_mount_status(mavlink_channel_t chan) = 0;
// handle a GIMBAL_REPORT message
virtual void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t *msg) {}
virtual void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg) {}
// handle a PARAM_VALUE message
virtual void handle_param_value(const mavlink_message_t *msg) {}
virtual void handle_param_value(const mavlink_message_t &msg) {}
// send a GIMBAL_REPORT message to the GCS
virtual void send_gimbal_report(const mavlink_channel_t chan) {}

View File

@ -114,7 +114,7 @@ void AP_Mount_SoloGimbal::send_mount_status(mavlink_channel_t chan)
/*
handle a GIMBAL_REPORT message
*/
void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t *msg)
void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg)
{
_gimbal.update_target(_angle_ef_target_rad);
_gimbal.receive_feedback(chan,msg);
@ -134,7 +134,7 @@ void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, const mav
}
}
void AP_Mount_SoloGimbal::handle_param_value(const mavlink_message_t *msg)
void AP_Mount_SoloGimbal::handle_param_value(const mavlink_message_t &msg)
{
_gimbal.handle_param_value(msg);
}
@ -142,7 +142,7 @@ void AP_Mount_SoloGimbal::handle_param_value(const mavlink_message_t *msg)
/*
handle a GIMBAL_REPORT message
*/
void AP_Mount_SoloGimbal::handle_gimbal_torque_report(mavlink_channel_t chan, const mavlink_message_t *msg)
void AP_Mount_SoloGimbal::handle_gimbal_torque_report(mavlink_channel_t chan, const mavlink_message_t &msg)
{
_gimbal.disable_torque_report();
}

View File

@ -39,9 +39,9 @@ public:
void send_mount_status(mavlink_channel_t chan) override;
// handle a GIMBAL_REPORT message
void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t *msg) override;
void handle_gimbal_torque_report(mavlink_channel_t chan, const mavlink_message_t *msg);
void handle_param_value(const mavlink_message_t *msg) override;
void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg) override;
void handle_gimbal_torque_report(mavlink_channel_t chan, const mavlink_message_t &msg);
void handle_param_value(const mavlink_message_t &msg) override;
// send a GIMBAL_REPORT message to the GCS
void send_gimbal_report(mavlink_channel_t chan) override;

View File

@ -41,10 +41,10 @@ gimbal_mode_t SoloGimbal::get_mode()
}
}
void SoloGimbal::receive_feedback(mavlink_channel_t chan, const mavlink_message_t *msg)
void SoloGimbal::receive_feedback(mavlink_channel_t chan, const mavlink_message_t &msg)
{
mavlink_gimbal_report_t report_msg;
mavlink_msg_gimbal_report_decode(msg, &report_msg);
mavlink_msg_gimbal_report_decode(&msg, &report_msg);
uint32_t tnow_ms = AP_HAL::millis();
_last_report_msg_ms = tnow_ms;

View File

@ -56,7 +56,7 @@ public:
}
void update_target(const Vector3f &newTarget);
void receive_feedback(mavlink_channel_t chan, const mavlink_message_t *msg);
void receive_feedback(mavlink_channel_t chan, const mavlink_message_t &msg);
void update_fast();
@ -72,7 +72,7 @@ public:
void disable_torque_report() { _gimbalParams.set_param(GMB_PARAM_GMB_SND_TORQUE, 0); }
void fetch_params() { _gimbalParams.fetch_params(); }
void handle_param_value(const mavlink_message_t *msg) {
void handle_param_value(const mavlink_message_t &msg) {
_gimbalParams.handle_param_value(msg);
}

View File

@ -181,10 +181,10 @@ void SoloGimbal_Parameters::update()
}
}
void SoloGimbal_Parameters::handle_param_value(const mavlink_message_t *msg)
void SoloGimbal_Parameters::handle_param_value(const mavlink_message_t &msg)
{
mavlink_param_value_t packet;
mavlink_msg_param_value_decode(msg, &packet);
mavlink_msg_param_value_decode(&msg, &packet);
AP_Logger *logger = AP_Logger::get_singleton();
if (logger != nullptr) {

View File

@ -53,7 +53,7 @@ public:
void set_param(gmb_param_t param, float value);
void update();
void handle_param_value(const mavlink_message_t *msg);
void handle_param_value(const mavlink_message_t &msg);
Vector3f get_accel_bias();
Vector3f get_accel_gain();