[[multicamera_pixracer_connection]]

Setup

install ardupilot
	https://ardupilot.org/dev/docs/building-setup-linux.html
install pymavlink
	sudo apt-get install libxml2-dev libxslt1-dev
	pip install pymavlink
sudo raspi-config
      Interfaces => Serial 
	disable login on serial "NO"
	enable hardware serial "YES"
	Serial (Pi3/Pi4)
		/dev/ttyS0
		8 = TX
		10 = RX
flight SITL
	Setup SITL
		https://ardupilot.org/dev/docs/setting-up-sitl-on-linux.html
		https://ardupilot.org/dev/docs/plane-sitlmavproxy-tutorial.html
	Output SITL telemetry to serial port
		https://ardupilot.org/dev/docs/using-sitl-for-ardupilot-testing.html#using-real-serial-devices
		https://ardupilot.org/dev/docs/learning-ardupilot-uarts-and-the-console.html
	start simulatiom
	        sim_vehicle.py -w -v ArduPlane -A "--uartC=uart:/dev/ttyS0:9600" --console --map
	        wp load Tools/autotest/CMAC-circuit.txt
	        mode auto
	        arm throttle
Wireing
	__Serial Data (mavlink)__
		     /--> Pi3 10 (RX)
	Pi4 8 (TX) --
		     \--> Pi Zero 10 (RX)
	__GND__
		/--> Pi3 6
	Pi4 6 --
		\--> Pi Zero 6
	
sudo raspi-config
      Interfaces => Serial 
	disable login on serial "NO"
	enable hardware serial "YES"
	Serial (Pi3/Pi4)
		/dev/ttyS0
		8 = TX
		10 = RX
	Serial (Pi Zero)
		/dev/ttyAMA0
		8 = TX
		10 = RX
install pymavlink
	sudo apt-get install libxml2-dev libxslt1-dev
	pip install pymavlink
Continous camera image triggering code with GPS input via mavlink
	git clone https://gitlab.com/searchwing/development/searchwing-pi
	edit file for serial port (ttyAMA0 @ Pi Zero / ttyS0 @ Pi3)	
	python3 continuous_capture_GPS.py 

Output

Pi4:

wp load Tools/autotest/CMAC-circuit.txt
MANUAL> Loaded 8 waypoints from Tools/autotest/CMAC-circuit.txt
...
APM: Flight plan received
Got MAVLink msg: MISSION_ACK {target_system : 255, target_component : 0, type : 0, mission_type : 0}
wp load m
MANUAL> Unknown command 'm'
mode auto
MANUAL> APM: Mission: 1 Takeoff
Got MAVLink msg: COMMAND_ACK {command : 11, result : 0}
AUTO> Mode AUTO
waypoint 1
arm throttle
AUTO> APM: Throttle armed
Got MAVLink msg: COMMAND_ACK {command : 400, result : 0}
APM: Armed AUTO, xaccel = -0.0 m/s/s, waiting 0.2 sec
APM: Triggered AUTO. GPS speed = 0.0
ARMED
APM: Holding course 35279 at 19.3m/s (0.1)
height 10
height 20
APM: Takeoff level-off starting at 16m
height 30
APM: Takeoff complete at 41.41m
APM: Mission: 2 WP
height 40
400
waypoint 2
200
height 50
height 60
height 70
height 80
height 100
Flight battery 90 percent
height 110
APM: Reached waypoint #2 dist 57m
APM: Mission: 3 WP
...

Pi Zero:

INFO:root:2019-12-15T15:04:13.362813.jpg captured (lon:149.1645948 , lat:-35.3649894)
DEBUG:root:pixhawk GPS msg:(lon:149.1645419 , lat:-35.3647957)
DEBUG:root:pixhawk GPS msg:(lon:149.1644866 , lat:-35.3646023)
DEBUG:root:pixhawk GPS msg:(lon:149.1644332 , lat:-35.3644077)
INFO:root:2019-12-15T15:04:16.374349.jpg captured (lon:149.1644332 , lat:-35.3644077)
DEBUG:root:pixhawk GPS msg:(lon:149.1643844 , lat:-35.3642113)
DEBUG:root:pixhawk GPS msg:(lon:149.1643412 , lat:-35.3640153)
DEBUG:root:pixhawk GPS msg:(lon:149.1643034 , lat:-35.3638182)
INFO:root:2019-12-15T15:04:19.378186.jpg captured (lon:149.1643034 , lat:-35.3638182)
DEBUG:root:pixhawk GPS msg:(lon:149.1642704 , lat:-35.3636195)
DEBUG:root:pixhawk GPS msg:(lon:149.1642417 , lat:-35.3634208)
DEBUG:root:pixhawk GPS msg:(lon:149.1642162 , lat:-35.3632233)

Pi3:

 
INFO:root:2019-12-15T15:04:13.611948.jpg captured (lon:149.1644866 , lat:-35.3646023)
DEBUG:root:pixhawk GPS msg:(lon:149.1644332 , lat:-35.3644077)
DEBUG:root:pixhawk GPS msg:(lon:149.1643844 , lat:-35.3642113)
DEBUG:root:pixhawk GPS msg:(lon:149.1643412 , lat:-35.3640153)
INFO:root:2019-12-15T15:04:16.631539.jpg captured (lon:149.1643412 , lat:-35.3640153)
DEBUG:root:pixhawk GPS msg:(lon:149.1643034 , lat:-35.3638182)
DEBUG:root:pixhawk GPS msg:(lon:149.1642704 , lat:-35.3636195)
DEBUG:root:pixhawk GPS msg:(lon:149.1642417 , lat:-35.3634208)
INFO:root:2019-12-15T15:04:19.648091.jpg captured (lon:149.1642417 , lat:-35.3634208)
DEBUG:root:pixhawk GPS msg:(lon:149.1642162 , lat:-35.3632233)
DEBUG:root:pixhawk GPS msg:(lon:149.1641924 , lat:-35.3630252)

Result

  • Splitting of TX from pixracer to two pi zeros works
  • Disconnection of data connection and reconnection is working
  • Synchronized image recording is possible
  • multicamera_pixracer_connection.txt
  • Last modified: 2020/02/28 16:17
  • by wf68spef