|
def | __init__ (self, target_system=0, target_component=0) |
|
def | add (self, w, comment='') |
|
def | add_latlonalt (self, lat, lon, altitude, terrain_alt=False) |
|
def | clear (self) |
|
def | count (self) |
|
def | insert (self, idx, w, comment='') |
|
def | is_location_command (self, cmd) |
|
def | load (self, filename) |
|
def | polygon (self, done=None) |
|
def | polygon_list (self) |
|
def | reindex (self) |
|
def | remove (self, w) |
|
def | save (self, filename) |
|
def | save_as_pb (self, filename) |
|
def | set (self, w, idx) |
|
def | view_indexes (self, done=None) |
|
def | view_list (self) |
|
def | wp (self, i) |
|
def | wp_is_loiter (self, i) |
|
MAVLink waypoint loader
Definition at line 26 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.__init__ |
( |
|
self, |
|
|
|
target_system = 0 , |
|
|
|
target_component = 0 |
|
) |
| |
def pymavlink.mavwp.MAVWPLoader._read_waypoints_pb_110 |
( |
|
self, |
|
|
|
file |
|
) |
| |
|
private |
def pymavlink.mavwp.MAVWPLoader._read_waypoints_v100 |
( |
|
self, |
|
|
|
file |
|
) |
| |
|
private |
read a version 100 waypoint
Definition at line 130 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader._read_waypoints_v110 |
( |
|
self, |
|
|
|
file |
|
) |
| |
|
private |
read a version 110 waypoint
Definition at line 177 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.add |
( |
|
self, |
|
|
|
w, |
|
|
|
comment = '' |
|
) |
| |
add a waypoint
Definition at line 63 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.add_latlonalt |
( |
|
self, |
|
|
|
lat, |
|
|
|
lon, |
|
|
|
altitude, |
|
|
|
terrain_alt = False |
|
) |
| |
add a point via latitude/longitude/altitude
Definition at line 94 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.clear |
( |
|
self | ) |
|
clear waypoint list
Definition at line 125 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.count |
( |
|
self | ) |
|
return number of waypoints
Definition at line 38 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.insert |
( |
|
self, |
|
|
|
idx, |
|
|
|
w, |
|
|
|
comment = '' |
|
) |
| |
insert a waypoint
Definition at line 72 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.is_location_command |
( |
|
self, |
|
|
|
cmd |
|
) |
| |
see if cmd is a MAV_CMD with a latitide/longitude.
We check if it has Latitude and Longitude params in the right indexes
Definition at line 324 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.load |
( |
|
self, |
|
|
|
filename |
|
) |
| |
load waypoints from a file.
returns number of waypoints loaded
Definition at line 270 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.polygon |
( |
|
self, |
|
|
|
done = None |
|
) |
| |
return a polygon for the waypoints
Definition at line 395 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.polygon_list |
( |
|
self | ) |
|
return a list of polygons for the waypoints
Definition at line 407 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.reindex |
( |
|
self | ) |
|
reindex waypoints
Definition at line 87 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.remove |
( |
|
self, |
|
|
|
w |
|
) |
| |
remove a waypoint
Definition at line 119 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.save |
( |
|
self, |
|
|
|
filename |
|
) |
| |
save waypoints to a file
Definition at line 311 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.save_as_pb |
( |
|
self, |
|
|
|
filename |
|
) |
| |
def pymavlink.mavwp.MAVWPLoader.set |
( |
|
self, |
|
|
|
w, |
|
|
|
idx |
|
) |
| |
set a waypoint
Definition at line 109 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.view_indexes |
( |
|
self, |
|
|
|
done = None |
|
) |
| |
return a list waypoint indexes in view order
Definition at line 337 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.view_list |
( |
|
self | ) |
|
return a list of polygon indexes lists for the waypoints
Definition at line 417 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.wp |
( |
|
self, |
|
|
|
i |
|
) |
| |
return a waypoint
Definition at line 42 of file mavwp.py.
def pymavlink.mavwp.MAVWPLoader.wp_is_loiter |
( |
|
self, |
|
|
|
i |
|
) |
| |
return true if waypoint is a loiter waypoint
Definition at line 51 of file mavwp.py.
pymavlink.mavwp.MAVWPLoader.colour_for_polygon |
pymavlink.mavwp.MAVWPLoader.last_change |
pymavlink.mavwp.MAVWPLoader.target_component |
pymavlink.mavwp.MAVWPLoader.target_system |
pymavlink.mavwp.MAVWPLoader.wpoints |
The documentation for this class was generated from the following file: