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

mavsys: mode: add solutions for setting AUTO.MISSION and AUTO.LOITER modes #814

Merged
merged 5 commits into from
Sep 20, 2017
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
8 changes: 8 additions & 0 deletions mavros/scripts/mavsys
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,15 @@ from mavros_msgs.srv import SetMode, StreamRate, StreamRateRequest


def do_mode(args):
<<<<<<< HEAD
base_mode = 0
=======
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

looks like rebase error ^^

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That's fixed @khancyr. thanks

# Setting to MAV_MODE_FLAG_CUSTOM_MODE_ENABLED is mandatory, so to change to
# a custom mode/submode.
# NOTE: In order to change to AUTO.MISSION on PX4 Pro, you need to disable
# datalink failsafe, which can be done by setting NAV_DLL_ACT to 0.
base_mode = 1 # 1 = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED
>>>>>>> 2221c7c... mavsys: add notes on how to change mode to AUTO.MISSION on PX4 Pro
custom_mode = ''

if args.custom_mode is not None:
Expand Down
22 changes: 11 additions & 11 deletions mavros_msgs/srv/SetMode.srv
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,17 @@
# http://wiki.ros.org/mavros/CustomModes

# basic modes from MAV_MODE
uint8 MAV_MODE_PREFLIGHT = 0
uint8 MAV_MODE_STABILIZE_DISARMED = 80
uint8 MAV_MODE_STABILIZE_ARMED = 208
uint8 MAV_MODE_MANUAL_DISARMED = 64
uint8 MAV_MODE_MANUAL_ARMED = 192
uint8 MAV_MODE_GUIDED_DISARMED = 88
uint8 MAV_MODE_GUIDED_ARMED = 216
uint8 MAV_MODE_AUTO_DISARMED = 92
uint8 MAV_MODE_AUTO_ARMED = 220
uint8 MAV_MODE_TEST_DISARMED = 66
uint8 MAV_MODE_TEST_ARMED = 194
uint8 MAV_MODE_PREFLIGHT = 0
uint8 MAV_MODE_STABILIZE_DISARMED = 80
uint8 MAV_MODE_STABILIZE_ARMED = 208
uint8 MAV_MODE_MANUAL_DISARMED = 64
uint8 MAV_MODE_MANUAL_ARMED = 192
uint8 MAV_MODE_GUIDED_DISARMED = 88
uint8 MAV_MODE_GUIDED_ARMED = 216
uint8 MAV_MODE_AUTO_DISARMED = 92
uint8 MAV_MODE_AUTO_ARMED = 220
uint8 MAV_MODE_TEST_DISARMED = 66
uint8 MAV_MODE_TEST_ARMED = 194

uint8 base_mode # filled by MAV_MODE enum value or 0 if custom_mode != ''
string custom_mode # string mode representation or integer
Expand Down