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

Guided Mode Movement and Commands for FIXED-WINGS #1044

Open
Ayvazof opened this issue Jul 24, 2020 · 3 comments
Open

Guided Mode Movement and Commands for FIXED-WINGS #1044

Ayvazof opened this issue Jul 24, 2020 · 3 comments

Comments

@Ayvazof
Copy link

Ayvazof commented Jul 24, 2020

The issue is that, that I need to control plane from script depending of external sensor only way I found is use RC OVERRIDE but it is not a good way how I understand. Is there some way do it right?
Thanks in advance

@myusf01
Copy link

myusf01 commented Oct 22, 2020

I've been looking for the same but I couldn't found any related documentation about to set yaw, pitch, roll like commands like in send_ned_velocity function or CMD_CONDITION_YAW. RC_OVERRIDE looks complicated and dangerous as far as I've seen in issues.

@HefnySco
Copy link
Contributor

HefnySco commented Oct 22, 2020 via email

@domnantas
Copy link

domnantas commented Mar 13, 2021

This was a wild ride, but I managed to figure it out.
First off, Ardupilot documentation lists MAV_CMD_NAV_WAYPOINT as the only message available for planes. Apparently that's not true, you can also use SET_ATTITUDE_TARGET! Dronekit does not mention that anywhere either. In fact, in set_attitude_target example it says (Copter Only). This was really confusing.

After browsing through some similar issues in this repo, I decided to try it out and it worked! Here's my implementation:

def send_set_attitude_target(roll=0, pitch=0, yaw=0, thrust=0.5):
    attitude = [np.radians(roll), np.radians(pitch), np.radians(yaw)]
    attitude_quaternion = quaternion.QuaternionBase(attitude)

    msg = vehicle.message_factory.set_attitude_target_encode(
        0, 0, 0,  # time_boot_ms, target_system, target_component
        0b10111000,  # type_mask https://mavlink.io/en/messages/common.html#ATTITUDE_TARGET_TYPEMASK
        attitude_quaternion,  # Attitude quaternion
        0, 0, 0,  # Rotation rates (ignored)
        thrust  # Between 0.0 and 1.0
    )

    vehicle.send_mavlink(msg)

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants