Skip to content

Commit

Permalink
Update mission_raw.py
Browse files Browse the repository at this point in the history
Updated [MAV_FRAME](https://mavlink.io/en/messages/common.html#MAV_FRAME) command from 6 (deprecated) to 3 (newly updated WGS84 + rel. system)

Also added a few comments to make comprehension easier

Refactored file
  • Loading branch information
ShafSpecs committed May 14, 2024
1 parent b7fb8ed commit c6e7ed0
Showing 1 changed file with 18 additions and 13 deletions.
31 changes: 18 additions & 13 deletions examples/mission_raw.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,29 +22,34 @@ async def run():


async def run_drone(drone):

mission_items = []

mission_items.append(mission_raw.MissionItem(
0, # start seq at 0
6,
16,
1, # first one is current
1,
0, 10, 0, float('nan'),
int(47.40271757 * 10**7),
int(8.54285027 * 10**7),
30.0,
0
0, # start seq at 0
3, # MAV_FRAME command. 3 is WGS84 + relative altitude
16, # command. 16 is a basic waypoint
1, # first one is current
1, # auto-continue. 1: True, 0: False
0, # param1 - hold time
10, # param2 - Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)
0, # param3 - 0 means it should pass through the waypoint normally
float('nan'), # param4 - Desired yaw angle at waypoint. NaN to use the current system yaw heading mode
int(47.40271757 * 10**7), # param5 - latitude (multiplying by 10^7 due to MAV_FRAME)
int(8.54285027 * 10**7), # param6 - longitude
30.0, # param7 - altitude
0 # mission_type. Specifies this item as a main command for the mission
))

mission_items.append(mission_raw.MissionItem(
1,
6,
3,
16,
0,
1,
0, 10, 0, float('nan'),
0,
10,
0,
float('nan'),
int(47.40271757 * 10**7),
int(8.54361892 * 10**7),
30.0,
Expand Down

0 comments on commit c6e7ed0

Please sign in to comment.