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

ExtLibs: setMountConfigure uses mav-cmd-do-mount-configure #3159

Merged
Merged
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
21 changes: 9 additions & 12 deletions ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs
Original file line number Diff line number Diff line change
Expand Up @@ -4469,18 +4469,15 @@ public void setDigicamControl(bool shot)
[Obsolete]
public void setMountConfigure(MAV_MOUNT_MODE mountmode, bool stabroll, bool stabpitch, bool stabyaw)
{
mavlink_mount_configure_t req = new mavlink_mount_configure_t();

req.target_system = MAV.sysid;
req.target_component = MAV.compid;
req.mount_mode = (byte) mountmode;
req.stab_pitch = (stabpitch == true) ? (byte) 1 : (byte) 0;
req.stab_roll = (stabroll == true) ? (byte) 1 : (byte) 0;
req.stab_yaw = (stabyaw == true) ? (byte) 1 : (byte) 0;

generatePacket((byte) MAVLINK_MSG_ID.MOUNT_CONFIGURE, req);
Thread.Sleep(20);
generatePacket((byte) MAVLINK_MSG_ID.MOUNT_CONFIGURE, req);
byte stab_roll = (stabroll == true) ? (byte) 1 : (byte) 0;
byte stab_pitch = (stabpitch == true) ? (byte) 1 : (byte) 0;
byte stab_yaw = (stabyaw == true) ? (byte) 1 : (byte) 0;

// p1 : mount mode
// p2, p3, p4 : stabilize roll, pitch, yaw
// p5, p6, p7 : empty
// no ack required
doCommand(MAV.sysid, MAV.compid, MAV_CMD.DO_MOUNT_CONFIGURE, (byte)mountmode, stab_roll, stab_pitch, stab_yaw, 0, 0, 0, false);
}

[Obsolete]
Expand Down