Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Get altitude from Pixhawk + update README #2

Open
wants to merge 4 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 8 additions & 7 deletions ArduPilotDriver.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,12 @@ def debug_GPS_vars():
time.sleep(1)
lat = ardupilot.location.global_frame.lat
lon = ardupilot.location.global_frame.lon
alt = ardupilot.location.global_frame.alt
roll = ardupilot.attitude.roll
pitch = ardupilot.attitude.pitch
yaw = ardupilot.heading
print("lat: {}, lon: {}, roll: {}, pitch: {}, yaw: {}"
.format(lat, lon, roll, pitch, yaw))
print("lat: {}, lon: {}, alt {}, roll: {}, pitch: {}, yaw: {}"
.format(lat, lon, alt, roll, pitch, yaw))


def get_args():
Expand All @@ -45,11 +46,12 @@ def get_args():
return parser.parse_args()


async def send_gps_message(websocket, lat, lon):
async def send_gps_message(websocket, lat, lon, alt):
msg = {
"type": "gps",
"lat": lat,
"lon": lon
"lon": lon,
"alt": alt
}
await websocket.send(json.dumps(msg))

Expand Down Expand Up @@ -78,8 +80,7 @@ def cleanup():
curr_time = time.perf_counter()
last_data_send_times = {
"gps": curr_time,
"orientation": curr_time,
"heading": curr_time
"orientation": curr_time
}

# From M8N documentation:
Expand All @@ -100,7 +101,7 @@ def gps_callback(self, _, frame):
print("GPS Fix:", ardupilot.gps_0.fix_type, frame)
if ardupilot.gps_0.fix_type > 1:
last_data_send_times["gps"] = curr_time
asyncio.run(send_gps_message(websocket, frame.lat, frame.lon))
asyncio.run(send_gps_message(websocket, frame.lat, frame.lon, frame.alt))

def orientation_callback(self, _, attitude):
curr_time = time.perf_counter()
Expand Down
11 changes: 2 additions & 9 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@ Make sure `tmux` is installed, if not then `sudo apt install tmux`. Then:
{
"type": "gps",
"lat": number,
"lon": number
"lon": number,
"alt": number
}
```

Expand All @@ -52,11 +53,3 @@ Make sure `tmux` is installed, if not then `sudo apt install tmux`. Then:
"yaw": number
}
```

### Heading
```
{
"type": "heading",
"heading": number
}
```