Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Copter: do-mount-control commands ignored if no mount #16864

Merged
merged 1 commit into from
Mar 16, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 9 additions & 6 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -685,15 +685,17 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i

MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t &packet)
{
// if the mount doesn't do pan control then yaw the entire vehicle instead:
switch (packet.command) {
#if HAL_MOUNT_ENABLED
case MAV_CMD_DO_MOUNT_CONTROL:
if (!copter.camera_mount.has_pan_control()) {
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) &&
!copter.camera_mount.has_pan_control()) {
copter.flightmode->auto_yaw.set_fixed_yaw(
(float)packet.param3 * 0.01f,
0.0f,
0,0);
0,
false);
}
break;
#endif
Expand Down Expand Up @@ -955,13 +957,14 @@ void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg)
switch (msg.msgid) {
#if HAL_MOUNT_ENABLED
case MAVLINK_MSG_ID_MOUNT_CONTROL:
if (!copter.camera_mount.has_pan_control()) {
// if the mount doesn't do pan control then yaw the entire vehicle instead:
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) &&
!copter.camera_mount.has_pan_control()) {
Comment on lines +961 to +962
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) &&
!copter.camera_mount.has_pan_control()) {
if ((copter.camera_mount.get_mount_type() == copter.camera_mount.MountType::Mount_Type_None)) {
return;
}
if (!copter.camera_mount.has_pan_control()) {

copter.flightmode->auto_yaw.set_fixed_yaw(
mavlink_msg_mount_control_get_input_c(&msg) * 0.01f,
0.0f,
0,
0);
false);

break;
}
Expand Down
7 changes: 5 additions & 2 deletions ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1452,9 +1452,12 @@ void ModeAuto::do_roi(const AP_Mission::Mission_Command& cmd)
void ModeAuto::do_mount_control(const AP_Mission::Mission_Command& cmd)
{
#if HAL_MOUNT_ENABLED
if (!copter.camera_mount.has_pan_control()) {
auto_yaw.set_fixed_yaw(cmd.content.mount_control.yaw,0.0f,0,0);
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) &&
!copter.camera_mount.has_pan_control()) {
auto_yaw.set_fixed_yaw(cmd.content.mount_control.yaw,0.0f,0,false);
}
// pass the target angles to the camera mount
copter.camera_mount.set_angle_targets(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw);
#endif
}
Expand Down