Skip to content

Commit

Permalink
Get altitude from Pixhawk + update README
Browse files Browse the repository at this point in the history
Retrieve altitude from Pixhawk using the global frame. The altitude is
relative to the mean sea level.

README updated with new message
  • Loading branch information
huttongrabiel committed May 14, 2024
1 parent 8d778f1 commit c832b82
Show file tree
Hide file tree
Showing 2 changed files with 36 additions and 1 deletion.
29 changes: 28 additions & 1 deletion ArduPilotDriver.py
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,22 @@ async def send_orientation_message(websocket, roll, pitch, yaw):
await websocket.send(json.dumps(msg))


async def send_heading_message(websocket, heading):
msg = {
"type": "heading",
"heading": heading
}
await websocket.send(json.dumps(msg))


async def send_altitude_message(websocket, altitude):
msg = {
"type": "altitude",
"altitude": altitude
}
await websocket.send(json.dumps(msg))


async def async_main():
args = get_args()
print("Waiting for ardupilot connection on port {}...".format(args.port))
Expand All @@ -79,7 +95,8 @@ def cleanup():
last_data_send_times = {
"gps": curr_time,
"orientation": curr_time,
"heading": curr_time
"heading": curr_time,
"altitude": curr_time
}

# From M8N documentation:
Expand Down Expand Up @@ -115,15 +132,25 @@ def orientation_callback(self, _, attitude):
asyncio.run(send_orientation_message(
websocket, attitude.roll, attitude.pitch, attitude.yaw))

def altitude_callback(self, _, altitude):
curr_time = time.perf_counter()
if curr_time >= last_data_send_times["altitude"] + 1./args.frequency:
if args.debug:
print("Altitude", altitude)
last_data_send_times["altitude"] = curr_time
asyncio.run(send_altitude_message(websocket, altitude))

ardupilot.add_attribute_listener("location.global_frame", gps_callback)
ardupilot.add_attribute_listener("attitude", orientation_callback)
ardupilot.add_attribute_listener("location.global_frame.alt", altitude_callback)

try:
await asyncio.Future()
except websockets.ConnectionClosed as e:
print(e)
ardupilot.remove_attribute_listener("location.global_frame", gps_callback)
ardupilot.remove_attribute_listener("attitude", orientation_callback)
ardupilot.remove_attribute_listener("location.global_frame.alt", altitude_callback)
print("Reconnecting to rover server...")
continue
except (websockets.WebSocketException, OSError):
Expand Down
8 changes: 8 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -60,3 +60,11 @@ Make sure `tmux` is installed, if not then `sudo apt install tmux`. Then:
"heading": number
}
```

### Altitude
```
{
"type": "altitude",
"altitude": number
}
```

0 comments on commit c832b82

Please sign in to comment.