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

MAV_CMD_CONDITION_YAW - shortest direction v2 #341

Merged
merged 1 commit into from
Nov 27, 2023
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
6 changes: 3 additions & 3 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -1003,9 +1003,9 @@
</entry>
<entry value="115" name="MAV_CMD_CONDITION_YAW" hasLocation="false" isDestination="false">
<description>Reach a certain target angle.</description>
<param index="1" label="Angle" units="deg">target angle, 0 is north</param>
<param index="2" label="Angular Speed" units="deg/s">angular speed</param>
<param index="3" label="Direction" minValue="-1" maxValue="1" increment="2">direction: -1: counter clockwise, 1: clockwise</param>
<param index="1" label="Angle" units="deg" minValue="0" maxValue="360">target angle [0-360]. Absolute angles: 0 is north. Relative angle: 0 is initial yaw. Direction set by param3.</param>
<param index="2" label="Angular Speed" units="deg/s" minValue="0">angular speed</param>
<param index="3" label="Direction" minValue="-1" maxValue="1" increment="1">direction: -1: counter clockwise, 0: shortest direction, 1: clockwise</param>
<param index="4" label="Relative" minValue="0" maxValue="1" increment="1">0: absolute angle, 1: relative offset</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
Expand Down
Loading