|
| 1 | + |
1 | 2 | """ |
2 | 3 | guided_set_speed_yaw.py: (Copter Only) |
3 | 4 |
|
|
6 | 7 | Example documentation: http://python.dronekit.io/examples/guided-set-speed-yaw-demo.html |
7 | 8 | """ |
8 | 9 |
|
9 | | -from dronekit import connect, VehicleMode, LocationGlobal |
| 10 | +from dronekit import connect, VehicleMode, LocationGlobal, LocationGlobalRelative |
10 | 11 | from pymavlink import mavutil # Needed for command message definitions |
11 | 12 | import time |
12 | 13 | import math |
@@ -132,34 +133,6 @@ def set_roi(location): |
132 | 133 | vehicle.send_mavlink(msg) |
133 | 134 |
|
134 | 135 |
|
135 | | -def set_speed(speed): |
136 | | - """ |
137 | | - Send MAV_CMD_DO_CHANGE_SPEED to change the current speed when travelling to a point. |
138 | | -
|
139 | | - In AC3.2.1 Copter will accelerate to this speed near the centre of its journey and then |
140 | | - decelerate as it reaches the target. In AC3.3 the speed changes immediately. |
141 | | -
|
142 | | - This method is only useful when controlling the vehicle using position/goto commands. |
143 | | - It is not needed when controlling vehicle movement using velocity components. |
144 | | -
|
145 | | - For more information see: |
146 | | - http://copter.ardupilot.com/common-mavlink-mission-command-messages-mav_cmd/#mav_cmd_do_change_speed |
147 | | - """ |
148 | | - # create the MAV_CMD_DO_CHANGE_SPEED command |
149 | | - msg = vehicle.message_factory.command_long_encode( |
150 | | - 0, 0, # target system, target component |
151 | | - mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, #command |
152 | | - 0, #confirmation |
153 | | - 0, #param 1 |
154 | | - speed, # speed |
155 | | - 0, 0, 0, 0, 0 #param 3 - 7 |
156 | | - ) |
157 | | - |
158 | | - # send command to vehicle |
159 | | - vehicle.send_mavlink(msg) |
160 | | - |
161 | | - |
162 | | - |
163 | 136 |
|
164 | 137 | """ |
165 | 138 | Functions to make it easy to convert between the different frames-of-reference. In particular these |
@@ -197,7 +170,14 @@ def get_location_metres(original_location, dNorth, dEast): |
197 | 170 | #New position in decimal degrees |
198 | 171 | newlat = original_location.lat + (dLat * 180/math.pi) |
199 | 172 | newlon = original_location.lon + (dLon * 180/math.pi) |
200 | | - return LocationGlobal(newlat, newlon,original_location.alt) |
| 173 | + if type(original_location) is LocationGlobal: |
| 174 | + targetlocation=LocationGlobal(newlat, newlon,original_location.alt) |
| 175 | + elif type(original_location) is LocationGlobalRelative: |
| 176 | + targetlocation=LocationGlobalRelative(newlat, newlon,original_location.alt) |
| 177 | + else: |
| 178 | + raise Exception("Invalid Location object passed") |
| 179 | + |
| 180 | + return targetlocation; |
201 | 181 |
|
202 | 182 |
|
203 | 183 | def get_distance_metres(aLocation1, aLocation2): |
@@ -315,9 +295,6 @@ def goto(dNorth, dEast, gotoFunction=vehicle.simple_goto): |
315 | 295 | targetLocation=get_location_metres(currentLocation, dNorth, dEast) |
316 | 296 | targetDistance=get_distance_metres(currentLocation, targetLocation) |
317 | 297 | gotoFunction(targetLocation) |
318 | | - |
319 | | - |
320 | | - |
321 | 298 |
|
322 | 299 | while vehicle.mode.name=="GUIDED": #Stop action if we are no longer in guided mode. |
323 | 300 | remainingDistance=get_distance_metres(vehicle.location.global_relative_frame, targetLocation) |
@@ -420,8 +397,10 @@ def send_global_velocity(velocity_x, velocity_y, velocity_z, duration): |
420 | 397 | the distance-to-target. |
421 | 398 | """ |
422 | 399 | print("TRIANGLE path using standard Vehicle.simple_goto()") |
423 | | -print("Set speed to 5m/s.") |
424 | | -set_speed(5) |
| 400 | + |
| 401 | +print("Set groundspeed to 5m/s.") |
| 402 | +vehicle.groundspeed=5 |
| 403 | + |
425 | 404 | print("Position North 80 West 50") |
426 | 405 | goto(80, -50) |
427 | 406 |
|
@@ -450,17 +429,17 @@ def send_global_velocity(velocity_x, velocity_y, velocity_z, duration): |
450 | 429 | print("TRIANGLE path using standard SET_POSITION_TARGET_GLOBAL_INT message and with varying speed.") |
451 | 430 | print("Position South 100 West 130") |
452 | 431 |
|
453 | | -print("Set speed to 5m/s.") |
454 | | -set_speed(5) |
| 432 | +print("Set groundspeed to 5m/s.") |
| 433 | +vehicle.groundspeed=5 |
455 | 434 | goto(-100, -130, goto_position_target_global_int) |
456 | 435 |
|
457 | | -print("Set speed to 15m/s (max).") |
458 | | -set_speed(15) |
| 436 | +print("Set groundspeed to 15m/s (max).") |
| 437 | +vehicle.groundspeed=15 |
459 | 438 | print("Position South 0 East 200") |
460 | 439 | goto(0, 260, goto_position_target_global_int) |
461 | 440 |
|
462 | | -print("Set speed to 10m/s (max).") |
463 | | -set_speed(10) |
| 441 | +print("Set airspeed to 10m/s (max).") |
| 442 | +vehicle.airspeed=10 |
464 | 443 |
|
465 | 444 | print("Position North 100 West 130") |
466 | 445 | goto(100, -130, goto_position_target_global_int) |
|
0 commit comments