Skip to content

Instantly share code, notes, and snippets.

@rjehangir
Created August 18, 2016 19:11
Show Gist options
  • Save rjehangir/973a2b4ef75e57690de6531f122a100d to your computer and use it in GitHub Desktop.
Save rjehangir/973a2b4ef75e57690de6531f122a100d to your computer and use it in GitHub Desktop.
#!/usr/bin/python
from pymavlink import mavutil
from pymavlink.dialects.v10 import common as mavlink
# UDP settings (must match a udpout port running on mavproxy)
address = 'localhost'
port = 9001
#master = mavutil.mavlink_connection(args.device, baud=args.baudrate, source_system=args.SOURCE_SYSTEM)
master = mavutil.mavlink_connection('udpout:'+address+':'+str(port))
# Send mock distance sensor measurements
current_distance = 100 # cm
while ( True ):
current_distance = current_distance + 10.5 # cm
print "Sending current_distance=%f cm to mavproxy on %s:%i" % (current_distance,address,port)
# distance_sensor_send(self, time_boot_ms, min_distance, max_distance, current_distance, type, id, orientation, covariance):
master.mav.distance_sensor_send(0, 0, 0, current_distance, 1, 0, 0, 0)
import time
time.sleep(1)
@rjehangir
Copy link
Author

rjehangir commented Aug 18, 2016

This runs on a Raspberry Pi that is connected to a Pixhawk. The Raspberry Pi is also running mavproxy with the following settings:

mavproxy.py --master /dev/ttyACM0,115200 \
            --out udpin:localhost:9000 \
            --out udpin:localhost:9001 \
            --out udpbcast:192.168.2.255:14550

Port 9001 is used for communication from this script. Make sure you add it to your mavproxy command.

Also, set the Pixhawk to accept a "mavlink rangefinder" by setting RNGFND_TYPE to "MAVLink".

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment