mirror of https://github.com/ArduPilot/ardupilot
Sub: calls to mount.set_angle_target set earth-frame or body-frame
this is a non-functional change
This commit is contained in:
parent
8f54957530
commit
d0c489a0be
|
@ -685,6 +685,6 @@ void Sub::do_roi(const AP_Mission::Mission_Command& cmd)
|
||||||
void Sub::do_mount_control(const AP_Mission::Mission_Command& cmd)
|
void Sub::do_mount_control(const AP_Mission::Mission_Command& cmd)
|
||||||
{
|
{
|
||||||
#if HAL_MOUNT_ENABLED
|
#if HAL_MOUNT_ENABLED
|
||||||
camera_mount.set_angle_targets(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw);
|
camera_mount.set_angle_target(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw, false);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -183,7 +183,7 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held)
|
||||||
|
|
||||||
case JSButton::button_function_t::k_mount_center:
|
case JSButton::button_function_t::k_mount_center:
|
||||||
#if HAL_MOUNT_ENABLED
|
#if HAL_MOUNT_ENABLED
|
||||||
camera_mount.set_angle_targets(0, 0, 0);
|
camera_mount.set_angle_target(0, 0, 0, false);
|
||||||
// for some reason the call to set_angle_targets changes the mode to mavlink targeting!
|
// for some reason the call to set_angle_targets changes the mode to mavlink targeting!
|
||||||
camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
|
camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -98,7 +98,7 @@ void Sub::init_ardupilot()
|
||||||
// initialise camera mount
|
// initialise camera mount
|
||||||
camera_mount.init();
|
camera_mount.init();
|
||||||
// This step ncessary so the servo is properly initialized
|
// This step ncessary so the servo is properly initialized
|
||||||
camera_mount.set_angle_targets(0, 0, 0);
|
camera_mount.set_angle_target(0, 0, 0, false);
|
||||||
// for some reason the call to set_angle_targets changes the mode to mavlink targeting!
|
// for some reason the call to set_angle_targets changes the mode to mavlink targeting!
|
||||||
camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
|
camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue