You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
When launching gz sim with docker containers running sim_vehicle.py, docker containers report no link.
Notes:
Multi vehicle sim on host machine (launching sim_vehicle.py in separate terminals instead of docker containers) works just fine.
Simulation also works fine when there is only a single vehicle.
Using Ubuntu 22.04.
Using Gazebo Garden.
Only tested with iris model.
Version
master
Platform
[ ] All
[ ] AntennaTracker
[ x ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine
Steps to Replicate
-- World, models, and dockerfile used here: resources.zip --
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).
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.
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);
}
Bug report
Issue details
When launching
gz sim
with docker containers runningsim_vehicle.py
, docker containers reportno link
.Notes:
Version
master
Platform
[ ] All
[ ] AntennaTracker
[ x ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine
Steps to Replicate
-- World, models, and dockerfile used here: resources.zip --
Launch
gz sim
with a modifiediris_runway.sdf
world that has two iris models withfdm_addr
configured to the docker host IP, and thefdm_port_in
of drone1 and drone2 to be configured to9002
and9012
respectively (based on instance number).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.Note: make sure to run
source ~/.profile
beforesim_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
The text was updated successfully, but these errors were encountered: