ArduPilot / ardupilot_gazebo

Plugins and models for vehicle simulation in Gazebo Sim with ArduPilot SITL controllers
GNU Lesser General Public License v3.0
91 stars 84 forks source link

Copter: Multi Vehicle SITL with docker not working #114

Open nifvimp opened 4 hours ago

nifvimp commented 4 hours ago

Bug report

Issue details

When launching gz sim with docker containers running sim_vehicle.py, docker containers report no link.

Notes:

Version

Platform

[ ] All [ ] AntennaTracker [ x ] Copter [ ] Plane [ ] Rover [ ] Submarine

Steps to Replicate

-- World, models, and dockerfile used here: resources.zip --

  1. Launch gz sim with a modified iris_runway.sdf world that has two iris models with fdm_addr configured to the docker host IP, and the fdm_port_in of drone1 and drone2 to be configured to 9002 and 9012 respectively (based on instance number).

  2. Launch two docker containers that are connected to a docker network bridge and have ArduPilot installed, then run sim_vehicle.py inside the two docker containers.

    • drone1
      sim_vehicle.py -v ArduCopter -f gazebo-iris --model JSON -I0 --sysid 1 --sim-address <host-ip>   
    • drone2
      sim_vehicle.py -v ArduCopter -f gazebo-iris --model JSON --I1 --sysid 2 --sim-address <host-ip>   

          Note: make sure to run source ~/.profile before sim_vehicle.py.

Logs

gz sim -v4 output with ardupilot_gazebo plugin complied with DEBUG_JSON_IO flag gz-sim-debug-json-io.txt

drone1 sim_vehicle.py output drone1-sim_vehicle.txt

drone2 sim_vehicle.py output drone2-sim_vehicle.txt

nifvimp commented 3 hours ago

A quick solution I found was to add a class member to SocketUDP that would store the ip_addr of the client and return a pointer to this string instead of the string returned by inet_ntoa in the SocketUDP::get_client_addr function.

SocketUDP.hh

class SocketUDP {
public:
  . . .

private:
    /// \brief File descriptor.
    struct sockaddr_in in_addr{};

    /// \brief File descriptor.
    int fd = -1;

    /// \brief Client address buffer.      <--- new addition
    char client_addr[16];

    /// \brief Poll for incoming data with timeout.
    bool pollin(uint32_t timeout_ms);

    /// \brief Make a sockaddr_in struct from address and port.
    void make_sockaddr(const char *address, uint16_t port,
                       struct sockaddr_in &sockaddr);
}

SocketUDP.cc

// new get_client_address function

void SocketUDP::get_client_address(const char *&ip_addr, uint16_t &port) {
    memcpy(this->client_addr, inet_ntoa(in_addr.sin_addr), 16);
    ip_addr = this->client_addr;
    port = ntohs(in_addr.sin_port);
}