I have been asked to install 2 Holybro DroneCan F9P receivers and a Here4 Unit.
I know the code can understand only2 and not 3, but is there a way to make all three units work but based on Node or GPS order setup 2 of them as GPS for Yaw?
Currently, the flight controller does not support a third GPS module.
However, the second GPS module in the GPS-for-Yaw function with dual F9P modules can output RTCM signals via a serial port and connect to the UART2 of the first GPS module.
U-Blox F9P MovingBase : ZED-F9P-MovingBase_AppNote_UBX-19009093
ArduPilot GPS FOR YAW: GPS for Yaw (aka Moving Baseline) — Copter documentation
Since these are DroneCan, there is no serious need to connect the serial cable. Since docs gives all info for setting up everything, including RTCM.
I know the firmware does not officially take 3 GPS units and i also know that for a year now Peter is looking into it.
I can connect all 3 through CAN ports but even though i have set NodeID 1 and 2 for the 2 holybro units and 3 for the Here4 unit it seems to jump at random to recognize my 1 and 2 GPS. I have always used only 2 GPS units at max and its not the first set of GPS for Yaw i have configured. For some reason i have been tasked to find if there is a 2 GPS solution possible.
If it is just for redundancy then put 1 Holybro F9P on CAN1 and the Here4 on CAN2 and hopefully they wont both be affected by the same issues.
If it’s primarily GPS-for-yaw then use the two Holybro’s.
That’d be my plan.
Thanx for the reply.
My plan was exactly the same but my issue is that they requested ill add a 3rd GPS and actually a Here4. It seems they have seen the matrice 600 and got the idea
3 are just not supported yet.
And all those Matrice’s with 3 GPSs sticking up were quite old tech too. One good one now is probably worth more than 3 of them
told them, but so far it did not make much difference
……………
Who is “them”?
I believe you may be able to compile your own build with “GPS_MAX_RECEIVERS” set to 3, This will disable GPS blending. You’ll only be able to use GPS_AUTO_SWITCH as either “UseBest”(1) or “Use primary if 3D fix or better”(3).
The code that handles the “UseBest” chooses the GPS that either has a better “lock status” or has the most satellites.
if (state[i].status > state[primary_instance].status) {
// we have a higher status lock, or primary is set to the blended GPS, change GPS
primary_instance = i;
_last_instance_swap_ms = now;
continue;
}
bool another_gps_has_1_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 1);
if (state[i].status == state[primary_instance].status && another_gps_has_1_or_more_sats) {
bool another_gps_has_2_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 2);
if ((another_gps_has_1_or_more_sats && (now - _last_instance_swap_ms) >= 20000) ||
(another_gps_has_2_or_more_sats && (now - _last_instance_swap_ms) >= 5000)) {
// this GPS has more satellites than the
// current primary, switch primary. Once we switch we will
// then tend to stick to the new GPS as primary. We don't
// want to switch too often as it will look like a
// position shift to the controllers.
primary_instance = i;
_last_instance_swap_ms = now;
}
}
The GPS lock statuses are ordered from worst to best here:
enum GPS_Status {
NO_GPS = 0, ///< No GPS connected/detected
NO_FIX = 1, ///< Receiving valid GPS messages but no lock
GPS_OK_FIX_2D = 2, ///< Receiving valid messages and 2D lock
GPS_OK_FIX_3D = 3, ///< Receiving valid messages and 3D lock
GPS_OK_FIX_3D_DGPS = 4, ///< Receiving valid messages and 3D lock with differential improvements
GPS_OK_FIX_3D_RTK_FLOAT = 5, ///< Receiving valid messages and 3D RTK Float
GPS_OK_FIX_3D_RTK_FIXED = 6, ///< Receiving valid messages and 3D RTK Fixed
};
the ones making the request for the build. solution was found and finally they accepted a single unit dual antenna gps for yaw and the here 4 as a secondary failsafe.