MAV_CMD_DO_SET_MODE all possible modes

I think that it is quite late reply, but I want to leave my answer for others who have the same problem.

You need to assign base_mode, main_mode, and sub_mode.
For instance, in order to trigger ‘position’ flight mode, you can use the following pymavlink code. I think that it will be same in dronekit code.

master.mav.command_long_send(
master.target_system, master.target_component,
mavutil.mavlink.MAV_CMD_DO_SET_MODE, 0,
base_mode, main_mode, sub_mode, 0, 0, 0, 0)

sub_mode is only defined for the AUTO_MOD

master.mav.command_long_send(
master.target_system, master.target_component,
mavutil.mavlink.MAV_CMD_DO_SET_MODE, 0,
217, 3, 0, 0, 0, 0, 0)

It seems likely to me that the base_mode value will be changed according to current flight mode (If it is incorrect, please correct me).

FYI, you can use the following main_mode, and sub_mode.

  1. Manual: base_mode:217, main_mode:1, sub_mode:0
  2. Stabilized: base_mode:209, main_mode:7, sub_mode:0
  3. Acro: base_mode:209, main_mode:5, sub_mode:0
  4. Rattitude: base_mode:193, main_mode:8, sub_mode:0
  5. Altitude: base_mode:193, main_mode:2, sub_mode:0
  6. Offboard: base_mode:209, main_mode:6, sub_mode:0
  7. Position: base_mode:209, main_mode:3, sub_mode:0
  8. Hold: base_mode:217, main_mode:4, sub_mode:3
  9. Missition: base_mode:157, main_mode:4, sub_mode:4
  10. Return: base_mode:157, main_mode:4, sub_mode:5
  11. Follow me: base_mode:157, main_mode:4, sub_mode:8

As I mentioned, the base_mode will be changed, but there are only 4 cases: 157, 193, 209 and 217. Thanks!

5 Likes