Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
A
Ardupilot
Manage
Activity
Members
Labels
Plan
Issues
0
Issue boards
Milestones
Wiki
Code
Merge requests
0
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
OpenSource
Ardupilot
Commits
28846c6c
Commit
28846c6c
authored
11 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
GCS_MAVLink: add DO_MOTOR_TEST message
parent
0408c116
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
+24
-0
24 additions, 0 deletions
libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
with
24 additions
and
0 deletions
libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
+
24
−
0
View file @
28846c6c
...
@@ -100,6 +100,17 @@
...
@@ -100,6 +100,17 @@
<param
index=
"7"
>
Empty
</param>
<param
index=
"7"
>
Empty
</param>
</entry>
</entry>
<entry
name=
"MAV_CMD_DO_MOTOR_TEST"
value=
"209"
>
<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=
"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=
"7"
>
Empty
</param>
</entry>
</enum>
</enum>
<!-- fenced mode enums -->
<!-- fenced mode enums -->
...
@@ -170,6 +181,19 @@
...
@@ -170,6 +181,19 @@
</entry>
</entry>
</enum>
</enum>
<!-- motor test type enum -->
<enum
name=
"MOTOR_TEST_THROTTLE_TYPE"
>
<entry
name=
"MOTOR_TEST_THROTTLE_PERCENT"
value=
"0"
>
<description>
throttle as a percentage from 0 ~ 100
</description>
</entry>
<entry
name=
"MOTOR_TEST_THROTTLE_PWM"
value=
"1"
>
<description>
throttle as an absolute PWM value (normally in range of 1000~2000)
</description>
</entry>
<entry
name=
"MOTOR_TEST_THROTTLE_PILOT"
value=
"2"
>
<description>
throttle pass-through from pilot's transmitter
</description>
</entry>
</enum>
</enums>
</enums>
<messages>
<messages>
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment