Skip to content

Instantly share code, notes, and snippets.

View Williangalvani's full-sized avatar

Willian Galvani Williangalvani

View GitHub Profile
@Williangalvani
Williangalvani / build.md
Last active March 14, 2024 20:39
bulding and debugging ardusub dev with gcc 10.2 for navigator

Instructions for building and debugging ArduSub in Blueos

This uses a fixed gcc version, 10.2, as that is what ardupilot is using, and seems to play along fine with glibc and gdbserver in blueos.

10.3 WILL NOT WORK IN BLUEOS

wget --no-clobber http://new.galvanicloop.com:8000/gcc-arm-10.2-2020.11-x86_64-arm-none-linux-gnueabihf.tar.xz
tar -xxvf gcc-arm-10.2-2020.11-x86_64-arm-none-linux-gnueabihf.tar.xz
git clone --recurse-submodules --branch Sub-4.1 https://github.com/ArduPilot/ardupilot.git
@Williangalvani
Williangalvani / speed_control.py
Created August 30, 2022 20:46
pymavlink speed ardusub
"""
Example of how to set target speed in guided mode with pymavlink
"""
import time
import math
# Import mavutil
from pymavlink import mavutil
# Imports for attitude
from pymavlink.quaternion import QuaternionBase
from pymavlink import mavutil
import time
############################## WARNING ################################
# THIS WILL DISABLE ARDUSUB'S ABILITIES TO CONTROL THE ROV BY ITSELF.
# USE WITH CAUTION
# MOTORS WILL SPIN WHEN THIS RUNS EVEN IF DISARMED
#######################################################################
# This example allows direct control of the thrusters, bypassing the
@Williangalvani
Williangalvani / versions.json
Last active September 2, 2020 13:17
for testing purposes
{
"stable": {
"dockers": {
"supervisor": {
"tag": "stable",
"image": "williangalvani/supervisor",
"enabled": true,
"webui": false,
"ports": {
"8080/tcp": 8080
#!/usr/bin/env python3
"""
This script is used to integrate the nortek DVL1000 with ardupilot.
The DVL must be outputting messages $PNORBT6 to port 9000 of whoever runs this script.
There must also be a mavlink connection avaiable at 0.0.0.0:14551 so the script can get
ATTITUDE messages
"""
import asyncio
@Williangalvani
Williangalvani / dvl_tcp.py
Created April 27, 2020 13:42
Waterlinked DVL Integration script (WIP)
#!/usr/bin/env python3
"""
This script is used to integrate the Waterlinked A50 DVL with ardupilot.
It uses a tcp connection to port
There must also be a mavlink connection avaiable at 0.0.0.0:14551 so the script can get
ATTITUDE messages
"""
import asyncio
from pymavlink import mavutil
@Williangalvani
Williangalvani / attitudeControl.py
Created January 14, 2020 21:25
Sets attitude for bluerov2 using pymavlink
# Import mavutil
from pymavlink import mavutil
from pymavlink.quaternion import QuaternionBase
import math
import time
import sys
ALT_HOLD_MODE = 2
def is_armed():
try:
@Williangalvani
Williangalvani / rccontrol.py
Created December 2, 2019 19:36
code to demonstrate weird behavior of ArduSub master
#This makes my thrusters go insane!
# Import mavutil
from pymavlink import mavutil
import time
# Create the connection
master = mavutil.mavlink_connection('udpin:0.0.0.0:14551')
# Wait a heartbeat before sending commands
master.wait_heartbeat()
@Williangalvani
Williangalvani / target_depth.py
Last active August 20, 2020 08:09
set target depth ardusub
#!/usr/bin/env python
# Script to set target depth in Ardusub 3.6 beta
# requires this commit: https://github.com/williangalvani/ardupilot/commit/85a41d5771ba9d64e594dcc0856b6a3906767c3f
from pymavlink import mavutil
# There is very likely a builtin in pymavlink for this, but I didn't find it
ALT_HOLD_MODE = 2
#!/usr/bin/env python
#simplePingExample.py
from brping import Ping1D
import time
import argparse
from builtins import input
##Parse Command line options