Skip to content

Commit 41fc0d2

Browse files
committed
add listener to set home location when a HOME_POSITION message is received from the vehicle
1 parent f60b81a commit 41fc0d2

File tree

1 file changed

+6
-1
lines changed

1 file changed

+6
-1
lines changed

dronekit/__init__.py

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1200,6 +1200,11 @@ def listener(self, name, msg):
12001200
self._wploader.expected_count = msg.count
12011201
self._master.waypoint_request_send(0)
12021202

1203+
1204+
@self.on_message(['HOME_POSITION'])
1205+
def listener(self, name, msg):
1206+
self._home_location = LocationGlobal(msg.latitude/1.0e7, msg.longitude/1.0e7, msg.altitude/1000.0);
1207+
12031208
@self.on_message(['WAYPOINT', 'MISSION_ITEM'])
12041209
def listener(self, name, msg):
12051210
if not self._wp_loaded:
@@ -1904,7 +1909,7 @@ def home_location(self, pos):
19041909
# Send MAVLink update.
19051910
self.send_mavlink(self.message_factory.command_long_encode(
19061911
0, 0, # target system, target component
1907-
mavutil.mavlink.MAV_CMD_DO_SET_HOME, # command
1912+
mavutil.mavlink.MAV_CMD_DO_SETH_OME, # command
19081913
0, # confirmation
19091914
2, # param 1: 1 to use current position, 2 to use the entered values.
19101915
0, 0, 0, # params 2-4

0 commit comments

Comments
 (0)