mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
AP_Mount: params always use set method
This commit is contained in:
parent
c1a9f75034
commit
47105f0b03
@ -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;
|
||||
}
|
||||
|
@ -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.
|
||||
|
Loading…
Reference in New Issue
Block a user