diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 03275760ef..b00b8f87a2 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -621,9 +621,9 @@ MAV_RESULT AP_Mount::handle_command_do_mount_configure(const mavlink_command_lon return MAV_RESULT_FAILED; } _backends[_primary]->set_mode((MAV_MOUNT_MODE)packet.param1); - state[_primary]._stab_roll = packet.param2; - state[_primary]._stab_tilt = packet.param3; - state[_primary]._stab_pan = packet.param4; + state[_primary]._stab_roll.set(packet.param2); + state[_primary]._stab_tilt.set(packet.param3); + state[_primary]._stab_pan.set(packet.param4); return MAV_RESULT_ACCEPTED; } diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index aa2555f03e..1222ff7749 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -60,9 +60,9 @@ void AP_Mount_Backend::set_target_sysid(uint8_t sysid) void AP_Mount_Backend::handle_mount_configure(const mavlink_mount_configure_t &packet) { set_mode((MAV_MOUNT_MODE)packet.mount_mode); - _state._stab_roll = packet.stab_roll; - _state._stab_tilt = packet.stab_pitch; - _state._stab_pan = packet.stab_yaw; + _state._stab_roll.set(packet.stab_roll); + _state._stab_tilt.set(packet.stab_pitch); + _state._stab_pan.set(packet.stab_yaw); } // process MOUNT_CONTROL messages received from GCS. deprecated.