-
Notifications
You must be signed in to change notification settings - Fork 15.1k
docs:ManualControlSetpoint uORB topic #26529
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
Open
hamishwillee
wants to merge
4
commits into
main
Choose a base branch
from
docs_manual_control_setpoint
base: main
Could not load branches
Branch not found: {{ refName }}
Loading
Could not load tags
Nothing to show
Loading
Are you sure you want to change the base?
Some commits from the old base branch may be removed from the timeline,
and old review comments may become outdated.
+31
−30
Open
Changes from 3 commits
Commits
Show all changes
4 commits
Select commit
Hold shift + click to select a range
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -1,45 +1,47 @@ | ||
| uint32 MESSAGE_VERSION = 0 | ||
| # Manual control setpoint message | ||
| # | ||
| # This message provides a representation of a manual control input, such as an RC controller or MAVLink controller (Joystick). | ||
| # It also defines the manual_control_setpoint topic, which represents the selected input. | ||
| # The message includes fields for the roll, pitch, yaw, throttle and flaps, along with auxiliary channels and button states. | ||
|
|
||
| uint64 timestamp # time since system start (microseconds) | ||
| uint64 timestamp_sample # the timestamp of the raw data (microseconds) | ||
| uint32 MESSAGE_VERSION = 0 | ||
|
|
||
| bool valid | ||
| uint64 timestamp # [us] Time since system start | ||
| uint64 timestamp_sample # [us] Timestamp of the raw data | ||
|
|
||
| uint8 SOURCE_UNKNOWN = 0 | ||
| uint8 SOURCE_RC = 1 # radio control (input_rc) | ||
| uint8 SOURCE_MAVLINK_0 = 2 # mavlink instance 0 | ||
| uint8 SOURCE_MAVLINK_1 = 3 # mavlink instance 1 | ||
| uint8 SOURCE_MAVLINK_2 = 4 # mavlink instance 2 | ||
| uint8 SOURCE_MAVLINK_3 = 5 # mavlink instance 3 | ||
| uint8 SOURCE_MAVLINK_4 = 6 # mavlink instance 4 | ||
| uint8 SOURCE_MAVLINK_5 = 7 # mavlink instance 5 | ||
| bool valid # True if the current data is valid. | ||
|
|
||
| uint8 data_source | ||
| uint8 data_source [@enum SOURCE] # Source of the manual control setpoint | ||
| uint8 SOURCE_UNKNOWN = 0 # Unknown source | ||
| uint8 SOURCE_RC = 1 # Radio control (input_rc) | ||
| uint8 SOURCE_MAVLINK_0 = 2 # MAVLink instance 0 | ||
| uint8 SOURCE_MAVLINK_1 = 3 # MAVLink instance 1 | ||
| uint8 SOURCE_MAVLINK_2 = 4 # MAVLink instance 2 | ||
| uint8 SOURCE_MAVLINK_3 = 5 # MAVLink instance 3 | ||
| uint8 SOURCE_MAVLINK_4 = 6 # MAVLink instance 4 | ||
| uint8 SOURCE_MAVLINK_5 = 7 # MAVLink instance 5 | ||
|
|
||
| # Any of the channels may not be available and be set to NaN | ||
| # to indicate that it does not contain valid data. | ||
|
|
||
| # Stick positions [-1,1] | ||
hamishwillee marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| # on a common RC mode 1/2/3/4 remote/joystick the stick deflection: -1 is down/left, 1 is up/right | ||
| # Note: QGC sends throttle/z in range [0,1000] - [0,1]. The MAVLink input conversion [0,1] to [-1,1] is at the moment kept backwards compatible. | ||
|
Comment on lines
25
to
26
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This wouldn't be rendered. Can this move up into the long description? |
||
| # Positive values are generally used for: | ||
| float32 roll # move right, positive roll rotation, right side down | ||
| float32 pitch # move forward, negative pitch rotation, nose down | ||
| float32 yaw # positive yaw rotation, clockwise when seen top down | ||
| float32 throttle # move up, positive thrust, -1 is minimum available 0% or -100% +1 is 100% thrust | ||
| float32 roll # [@range -1,1] [@invalid NaN] Positive values are generally used for: move right, positive roll rotation, right side down | ||
| float32 pitch # [@range -1,1] [@invalid NaN] Positive values are generally used for: move forward, negative pitch rotation, nose down | ||
| float32 yaw # [@range -1,1] [@invalid NaN] Positive values are generally used for: positive yaw rotation, clockwise when seen top down | ||
| float32 throttle # [@range -1,1] [@invalid NaN] Positive values are generally used for: move up, positive thrust, -1 is minimum available 0% or -100% +1 is 100% thrust | ||
|
|
||
| float32 flaps # position of flaps switch/knob/lever [-1, 1] | ||
| float32 flaps # [@range -1, 1] [@invalid NaN] Position of flaps switch/knob/lever | ||
|
|
||
| float32 aux1 | ||
| float32 aux2 | ||
| float32 aux3 | ||
| float32 aux4 | ||
| float32 aux5 | ||
| float32 aux6 | ||
| float32 aux1 # [@range -1,1] [@invalid NaN] Auxiliary channel 1 | ||
| float32 aux2 # [@range -1,1] [@invalid NaN] Auxiliary channel 2 | ||
| float32 aux3 # [@range -1,1] [@invalid NaN] Auxiliary channel 3 | ||
| float32 aux4 # [@range -1,1] [@invalid NaN] Auxiliary channel 4 | ||
| float32 aux5 # [@range -1,1] [@invalid NaN] Auxiliary channel 5 | ||
| float32 aux6 # [@range -1,1] [@invalid NaN] Auxiliary channel 6 | ||
|
|
||
| bool sticks_moving | ||
| bool sticks_moving # True if any of the values are changing. | ||
|
|
||
| uint16 buttons # From uint16 buttons field of Mavlink manual_control message | ||
| uint16 buttons # From uint16 buttons field of MAVLink MANUAL_CONTROL message | ||
|
|
||
| # TOPICS manual_control_setpoint manual_control_input | ||
| # DEPRECATED: float32 x | ||
|
|
||
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Is this accurate and sufficient? Essentially we want to define the uses, publishers and consumers.
As stated I think this represents each of the inputs, and also it represent a selected input. However it might be a synthesized input. Can you confirm?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
What do you mean by synthesized? Since input can be coming from Mavlink MANUAL_CONTROL messages you have no idea how that was produced. Usually joystick, but could be generated by anything.