Browse Source

Sub: calls to mount.set_angle_target set earth-frame or body-frame

this is a non-functional change
apm_2208
Randy Mackay 3 years ago
parent
commit
d0c489a0be
  1. 2
      ArduSub/commands_logic.cpp
  2. 2
      ArduSub/joystick.cpp
  3. 2
      ArduSub/system.cpp

2
ArduSub/commands_logic.cpp

@ -685,6 +685,6 @@ void Sub::do_roi(const AP_Mission::Mission_Command& cmd) @@ -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)
{
#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
}

2
ArduSub/joystick.cpp

@ -183,7 +183,7 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held) @@ -183,7 +183,7 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held)
case JSButton::button_function_t::k_mount_center:
#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!
camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
#endif

2
ArduSub/system.cpp

@ -98,7 +98,7 @@ void Sub::init_ardupilot() @@ -98,7 +98,7 @@ void Sub::init_ardupilot()
// initialise camera mount
camera_mount.init();
// 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!
camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
#endif

Loading…
Cancel
Save