Hi, I’m working on the first step to fly multiple quadcopters using Dronecore.
However, I found that dronecore assigns UUID using the version of autopilot.
Specifically, in the file ‘mavlink_system.cpp’,
void MAVLinkSystem::process_autopilot_version(const mavlink_message_t &message)
{
// Ignore if they don’t come from the autopilot component
if (message.compid != MAVLinkCommands::DEFAULT_COMPONENT_ID_AUTOPILOT) {
return;
}
mavlink_autopilot_version_t autopilot_version;
mavlink_msg_autopilot_version_decode(&message, &autopilot_version);
_supports_mission_int =
((autopilot_version.capabilities & MAV_PROTOCOL_CAPABILITY_MISSION_INT) ? true : false);
if (_uuid == 0 && autopilot_version.uid != 0) {
// This is the best case. The system has a UUID and we were able to get it.
**_uuid = autopilot_version.uid;**
} else if (_uuid == 0 && autopilot_version.uid == 0) {
// This is not ideal because the system has no valid UUID.
// In this case we use the mavlink system ID as the UUID.
_uuid = _system_id;
} else if (_uuid != autopilot_version.uid) {
// TODO: this is bad, we should raise a flag to invalidate system.
LogErr() << "Error: UUID changed";
}
_uuid_initialized = true;
set_connected();
_autopilot_version_pending = false;
unregister_timeout_handler(_autopilot_version_timed_out_cookie);
}
Thus when I try to connect multiple drones on the system, dronecore assigns identical UUID because all my drones use identical PX4 version.
I also found that UUID is assigned by using the system id on the other parts(yeah, that’s what I expected), so I modify the source code, rebuild the library, and finally I succeed to assign unique UUID using system ID.
However, I wonder there were proper ways to assign UUID using system ID, rather modify the source code.
Is there are good ways to achieve my goal?
Please give teach to newcomer:joy: