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

Add MAV_CMD_DO_SET_MOTOR definition #27

Merged
merged 1 commit into from May 4, 2017
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
18 changes: 15 additions & 3 deletions message_definitions/v1.0/common.xml
Expand Up @@ -1137,12 +1137,12 @@
</entry>
<entry value="209" name="MAV_CMD_DO_MOTOR_TEST">
<description>Mission command to perform motor test</description>
<param index="1">motor sequence number (a number from 1 to max number of motors on the vehicle)</param>
<param index="1">motor number (a number from 1 to max number of motors on the vehicle)</param>
<param index="2">throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)</param>
<param index="3">throttle</param>
<param index="4">timeout (in seconds)</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="5">motor count (number of motors to test to test in sequence, waiting for the timeout above between them; 0=1 motor, 1=1 motor, 2=2 motors...)</param>
<param index="6">motor test order (See MOTOR_TEST_ORDER enum)</param>
<param index="7">Empty</param>
</entry>
<entry value="210" name="MAV_CMD_DO_INVERTED_FLIGHT">
Expand Down Expand Up @@ -2311,6 +2311,18 @@
</entry>
</enum>
<!-- motor test type enum -->
<enum name="MOTOR_TEST_ORDER">
<entry name="MOTOR_TEST_ORDER_DEFAULT" value="0">
<description>default autopilot motor test method</description>
</entry>
<entry name="MOTOR_TEST_ORDER_SEQUENCE" value="1">
<description>motor numbers are specified as their index in a predefined vehicle-specific sequence</description>
</entry>
<entry name="MOTOR_TEST_ORDER_BOARD" value="2">
<description>motor numbers are specified as the output as labeled on the board</description>
</entry>
</enum>
<!-- motor test throttle type enum -->
<enum name="MOTOR_TEST_THROTTLE_TYPE">
<entry value="0" name="MOTOR_TEST_THROTTLE_PERCENT">
<description>throttle as a percentage from 0 ~ 100</description>
Expand Down