Problem setting GPS Start Point via MavLink to send vision-based coordinate

I successfully developed a vision-based navigation system for the Arducopter and the Raspberry Pi Zero 2W as a board computer; it works really well on multiple drones. I am very thankful to the community for its help at the start of the development. Now I am trying to adopt this to arduplane/vtols and I need help. The problem is that without a real GPS, I can’t set the start point. In Mission Planner, I am getting 0 0 as the GPS coordinate. I connect the Raspberry Pi to FC using UARTs and manage using MAVLink2 (ArduPilot Mega dialect). In ArduCopter, as soon as I send set_gps_global_origin and set_gps_global_origin, the start point appears in Mission Planner. But this does not work for ArduPlane. I also tried CMD_DO_SET_HOME:

void send_plane_set_home(float lat_deg, float lon_deg, float alt_m){
  mavlink_message_t msg;
  const int32_t lat_i = (int32_t)(lat_deg * 1e7);
  const int32_t lon_i = (int32_t)(lon_deg * 1e7);
  mavlink_command_int_t cmd{};
  cmd.target_system    = pilot::mavlink::VEHICLE_SYSTEM_ID;   // 1
  cmd.target_component = pilot::mavlink::VEHICLE_COMPONENT_ID;
  cmd.frame            = MAV_FRAME_GLOBAL; 
  cmd.command          = MAV_CMD_DO_SET_HOME;
  cmd.current          = 0;
  cmd.autocontinue     = 0;
  cmd.param1           = 0.0f;
  cmd.param2           = 0.0f;
  cmd.param3           = 0.0f;
  cmd.param4           = 0.0f;
  cmd.x                = lat_i;
  cmd.y                = lon_i;
  cmd.z                = alt_m;
  mavlink_msg_command_int_encode(
    pilot::mavlink::SYSTEM_ID,     // my companion sysid (100)
    pilot::mavlink::COMPONENT_ID,  // my companion compid (191)
    &msg,
    &cmd    
  );
  mav().add_to_queue(msg);
}

But it does not help as well… I tried sending GPS_INPUT, but nothing helps; the start point does not appear… Please help, this is the only showstopper. By logging more, the system performs better for planes than for copters, even with higher precision.

It constantly tells “EKF3 waiting for GPS config data“
I have set
GPS_AUTO_CONFIG = 0
I have set sources to GPS and GPS1_TYPE =MAVLINK, I send GPS_INPUT messages, but it seems that nothing of that is really accepted.

Solved, at least partially. There was a missing MAVLink GPS in the firmware. Now I may set the start point sending GPS_INPUT, but this is not too good because I prefer vision_estimate (there is a stamp required if the coordinate changes essentially when I make a global correction).

Diving deeper. Visual odometry without GPS (fake or actual) is impossible due to code:

bool NavEKF3_core::InitialiseFilterBootstrap(void)
{
  // If we are a plane and don't have GPS lock then don't initialise
  if (assume_zero_sideslip() && AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
      statesInitialised = false;
      return false;
  }

I think it should be changed to

if (assume_zero_sideslip() &&dal.gps().status(preferred_gps) < AP_DAL_GPS::GPS_OK_FIX_3D &&
!frontend->sources.ext_nav_enabled()) {

We will test it soon.

1 Like

Confirmed. This is the solution.

1 Like