Current Setup
I am trying to utilize Gazebo with SITL and Vagrant I am running Ardupilot at HEAD(7e89591) and am running Ubuntu 18.04LTS on my host and the vagrant box is disco64. I am able to run SITL in vagrant as per the [wiki tutorial](file:///home/braedon/Repositories/ardupilot_wiki/dev/build/html/docs/setting-up-sitl-using-vagrant.html) and connect from my host machine with mavproxy.
Adding Gazebo
I am using the built-in Ardupilot gazebo plugin which works properly when running sim_vehicle on my host machine (Tested by taking off and viewing results in gazebo). Reading through the plugins source code it can be seen that the plugin Recieves info on 127.0.0.1:9002 and sends it on 127.0.0.1:9003. Since there is no ardupilot.vagrant check for gazebo I assumed I needed to change 127.0.0.1 to 10.0.2.2 in order to communicate with gazebo running on the host so I set SITL sim-address to 10.0.2.2 with the command
vagrant ssh -c "sim_vehicle.py -j 2 -A '--sim-address 10.0.2.2' -v ArduCopter -f gazebo-iris"
This allowed gazebo to connect giving the gazebo debug message
[Dbg] [ArduCopterPlugin.cc:573] ArduCopter controller online detected.
Yet the Mavproxy instance that is launched to run the mavinit.scr failed to connect to the Ardupilot instance and attempts to connect mavproxy manually from another terminal from inside vagrant and from the host machine all failed(ports were found with trailing ss and lsof commands). This error happened with and without adding the -A option and as best I can tell is happening because of the running of SITL Gazebo.
Conclusion
There are definite gaps in my knowledge as to how the setting of the SITL sim-address would affect things like mavproxy’s --sitl parameter since they are unrelated ports. But I am wondering is there something in the SITL Gazebo that would affect mavproxy’s ability to connect? If anyone has any insight into making this work or how this system works I’d be interested in hearing about it. Thanks!
Command Outputs with gazebo
Command used to launch vagrant
vagrant ssh -c "sim_vehicle.py -j 2 -A '--sim-address 10.0.2.2' -v ArduCopter -f gazebo-iris"
Command sim_vehicle uses to launch ardupilot
/vagrant/build/sitl/bin/arducopter -S -I0 --model gazebo-iris --speedup 1 --sim-address 10.0.2.2 --defaults /vagrant/Tools/autotest/default_params/copter.parm,/vagrant/Tools/autotest/default_params/gazebo-iris.parm
Output of lsof -p … | egrep ‘TCP|UDP’
arducopte 14636 vagrant 3u sock 0,9 0t0 132467 protocol: TCP arducopte 14636 vagrant 4u IPv4 132468 0t0 UDP *:5501 arducopte 14636 vagrant 5u IPv4 132469 0t0 UDP localhost:53568->localhost:5503 arducopte 14636 vagrant 6u IPv4 132470 0t0 UDP *:9003 arducopte 14636 vagrant 7u IPv4 132471 0t0 TCP *:5760 (LISTEN) arducopte 14636 vagrant 8u IPv4 132472 0t0 TCP localhost:5760->localhost:59682 (ESTABLISHED)
Output of ss -tulw
Netid State Recv-Q Send-Q Local Address:Port Peer Address:Port icmp6 UNCONN 0 0 *%enp0s3:ipv6-icmp *:* udp UNCONN 0 0 127.0.0.53%lo:domain 0.0.0.0:* udp UNCONN 0 0 10.0.2.15%enp0s3:bootpc 0.0.0.0:* udp UNCONN 0 0 0.0.0.0:43440 0.0.0.0:* udp UNCONN 0 0 0.0.0.0:9003 0.0.0.0:* udp UNCONN 0 0 0.0.0.0:mdns 0.0.0.0:* udp UNCONN 0 0 0.0.0.0:5501 0.0.0.0:* udp UNCONN 0 0 [::]:51879 [::]:* udp UNCONN 0 0 [::]:mdns [::]:* tcp LISTEN 0 128 127.0.0.1:6010 0.0.0.0:* tcp LISTEN 0 128 127.0.0.1:6011 0.0.0.0:* tcp LISTEN 0 5 0.0.0.0:5760 0.0.0.0:* tcp LISTEN 0 128 127.0.0.53%lo:domain 0.0.0.0:* tcp LISTEN 0 128 0.0.0.0:ssh 0.0.0.0:* tcp LISTEN 0 128 [::1]:6010 [::]:* tcp LISTEN 0 128 [::1]:6011 [::]:* tcp LISTEN 0 128 [::]:ssh [::]:*
Contents of ardupilot terminal
Set parameter SIM_SPEEDUP to 1.000000 Starting SITL Gazebo Bind 127.0.0.1:9003 for SITL in Setting Gazebo interface to 10.0.2.2:9002 Starting sketch 'ArduCopter' Starting SITL input Using Irlock at port : 9005 bind port 5760 for 0 Serial port 0 on TCP port 5760 Waiting for connection .... Connection on serial port 0 Loaded defaults from /vagrant/Tools/autotest/default_params/copter.parm,/vagrant/Tools/autotest/default_params/gazebo-iris.parm Home: -35.363262 149.165237 alt=584.000000m hdg=353.000000
Contents of vagrant terminal (post build)
'build' finished successfully (3.104s) SIM_VEHICLE: Using defaults from (/vagrant/Tools/autotest/default_params/copter.parm,/vagrant/Tools/autotest/default_params/gazebo-iris.parm) SIM_VEHICLE: Run ArduCopter SIM_VEHICLE: "/vagrant/Tools/autotest/run_in_terminal_window.sh" "ArduCopter" "/vagrant/build/sitl/bin/arducopter" "-S" "-I0" "--model" "gazebo-iris" "--speedup" "1" "--defaults" "/vagrant/Tools/autotest/default_params/copter.parm,/vagrant/Tools/autotest/default_params/gazebo-iris.parm" SIM_VEHICLE: Run MavProxy SIM_VEHICLE: "mavproxy.py" "--master" "tcp:127.0.0.1:5760" "--sitl" "127.0.0.1:5501" "--out" "10.0.2.2:14550" "--out" "10.0.2.2:14551" RiTW: Starting ArduCopter : /vagrant/build/sitl/bin/arducopter -S -I0 --model gazebo-iris --speedup 1 --defaults /vagrant/Tools/autotest/default_params/copter.parm,/vagrant/Tools/autotest/default_params/gazebo-iris.parm Connect tcp:127.0.0.1:5760 source_system=255 Running script (/home/vagrant/.mavinit.scr) Running script /home/vagrant/.mavinit.scr -> module load graph Loaded module graph -> set moddebug 3 -> module load msg Loaded module msg -> alias add fence-dalby fence load /home/pbarker/rc/ardupilot/Tools/autotest/ArduPlane-Missions/Dalby-OBC2016-fence.txt -> alias add wp-dalby wp load /home/pbarker/rc/cuav/script/OBC2016/mission-plane.txt -> alias add wp-dalby-heli wp load /home/pbarker/rc/cuav/script/OBC2016/mission-heli.txt -> alias add grcall graph RC_CHANNELS.chan1_raw RC_CHANNELS.chan2_raw RC_CHANNELS.chan3_raw RC_CHANNELS.chan4_raw RC_CHANNELS.chan5_raw RC_CHANNELS.chan6_raw RC_CHANNELS.chan7_raw RC_CHANNELS.chan8_raw RC_CHANNELS.chan9_raw RC_CHANNELS.chan10_raw RC_CHANNELS.chan11_raw RC_CHANNELS.chan12_raw -> alias add grchigh graph SERVO_OUTPUT_RAW.servo7_raw SERVO_OUTPUT_RAW.servo8_raw SERVO_OUTPUT_RAW.servo9_raw SERVO_OUTPUT_RAW.servo10_raw SERVO_OUTPUT_RAW.servo11_raw SERVO_OUTPUT_RAW.servo12_raw -> module load devop Loaded module devop -> alias add old devop read i2c bob 0 0x52 0xc0 1 -> alias add newx devop i2c read 0 0x55 0 16 -> alias add new devop i2c read 1 0x1e 0x00 1 -> alias add i2cscan devop i2c scan 1 -> alias add spiread devop spi read mpu6000 0xf5 1 -> alias add bob long set_message_interval Log Directory: Telemetry log: mav.tlog Waiting for heartbeat from tcp:127.0.0.1:5760 MAV> link 1 down
Output of normal SITL Launch
Command used to start vagrant
`vagrant ssh -c “sim_vehicle.py -j 2 -v ArduCopter”
Command sim_vehicle uses to launch ardupilot
/vagrant/build/sitl/bin/arducopter -S -I0 --model + --speedup 1 --defaults /vagrant/Tools/autotest/default_params/copter.parm
Output of lsof -p … | egrep ‘TCP|UDP’
arducopte 14310 vagrant 3u sock 0,9 0t0 130928 protocol: TCP arducopte 14310 vagrant 4u IPv4 130929 0t0 UDP *:5501 arducopte 14310 vagrant 5u IPv4 130930 0t0 UDP localhost:52848->localhost:5503 arducopte 14310 vagrant 6u IPv4 130931 0t0 TCP *:5760 (LISTEN) arducopte 14310 vagrant 7u IPv4 130932 0t0 TCP localhost:5760->localhost:59678 (ESTABLISHED) arducopte 14310 vagrant 9u IPv4 130933 0t0 TCP *:5762 (LISTEN) arducopte 14310 vagrant 10u IPv4 130934 0t0 TCP *:5763 (LISTEN)
Output of ss -tulw
Netid State Recv-Q Send-Q Local Address:Port Peer Address:Port icmp6 UNCONN 0 0 *%enp0s3:ipv6-icmp *:* udp UNCONN 0 0 127.0.0.53%lo:domain 0.0.0.0:* udp UNCONN 0 0 10.0.2.15%enp0s3:bootpc 0.0.0.0:* udp UNCONN 0 0 0.0.0.0:43265 0.0.0.0:* udp UNCONN 0 0 0.0.0.0:43440 0.0.0.0:* udp UNCONN 0 0 127.0.0.1:9005 0.0.0.0:* udp UNCONN 0 0 0.0.0.0:60530 0.0.0.0:* udp UNCONN 0 0 0.0.0.0:mdns 0.0.0.0:* udp UNCONN 0 0 0.0.0.0:5501 0.0.0.0:* udp UNCONN 0 0 [::]:51879 [::]:* udp UNCONN 0 0 [::]:mdns [::]:* tcp LISTEN 0 128 127.0.0.1:6010 0.0.0.0:* tcp LISTEN 0 128 127.0.0.1:6011 0.0.0.0:* tcp LISTEN 0 5 0.0.0.0:5760 0.0.0.0:* tcp LISTEN 0 5 0.0.0.0:5762 0.0.0.0:* tcp LISTEN 0 5 0.0.0.0:5763 0.0.0.0:* tcp LISTEN 0 128 127.0.0.53%lo:domain 0.0.0.0:* tcp LISTEN 0 128 0.0.0.0:ssh 0.0.0.0:* tcp LISTEN 0 128 [::1]:6010 [::]:* tcp LISTEN 0 128 [::1]:6011 [::]:* tcp LISTEN 0 128 [::]:ssh [::]:*
Contents of ardupilot terminal
Set parameter SIM_SPEEDUP to 1.000000 Starting sketch 'ArduCopter' Starting SITL input Using Irlock at port : 9005 bind port 5760 for 0 Serial port 0 on TCP port 5760 Waiting for connection .... Connection on serial port 0 Loaded defaults from /vagrant/Tools/autotest/default_params/copter.parm Home: -35.363262 149.165237 alt=584.000000m hdg=353.000000 Smoothing reset at 0.001 bind port 5762 for 2 Serial port 2 on TCP port 5762 bind port 5763 for 3 Serial port 3 on TCP port 5763 validate_structures:414: Validating structures Loaded defaults from /vagrant/Tools/autotest/default_params/copter.parm