ModalAI Forum
    • Categories
    • Recent
    • Tags
    • Popular
    • Users
    • Groups
    • Register
    • Login
    1. Home
    2. necurran
    N
    • Profile
    • Following 0
    • Followers 0
    • Topics 1
    • Posts 3
    • Best 0
    • Controversial 0
    • Groups 0

    necurran

    @necurran

    0
    Reputation
    2
    Profile views
    3
    Posts
    0
    Followers
    0
    Following
    Joined Last Online

    necurran Unfollow Follow

    Latest posts made by necurran

    • RE: fc_sensor_get_time_offset functionality

      In fact, I think the whole voxl-mavlink-server scheme to set the system time from the SYSTEM_TIME mavlink message is fundamentally flawed for the case when PX4 is run on SLPI. The SYSTEM_TIME message emitted from voxl-px4 uses the system clock of the apps processor as it's time basis. So essentially, it either

      1. never changes the system clock if the offset between SLPI monotonic clock and apps monotonic clock is less than ten seconds
      2. continually sets the clock to either the future or the past by the offset of the monotonic clocks in the case where the offset is greater than 10 seconds

      It seems like this system should really be based on GNSS clock time instead of the SYSTEM_TIME message for this setup.

      posted in Ask your questions right here!
      N
      necurran
    • RE: fc_sensor_get_time_offset functionality

      @Eric-Katzfey Thanks

      I think this is causing issues with the system clock synchronization in voxl-mavlink-server when the apps processor is soft rebooted. This code in drv_hrt.cpp in PX4 posix common source seems to be to blame. This is correct for computing the offset between the monotonic clocks, but it seems to me as if it should not be used for CLOCK_REALTIME on the apps processor. As you reboot the apps more and more, the fc_sensor_get_time_offset() result grows, eventually to the point where it is greater than the 10 second gap that is enforced in voxl-mavlink-server. And setting the system clock on the apps processor never actually changes the gap in the monotonic clocks, so it just constantly loops while setting the apps system clock over and over again in the mavlink server.

      I was able to recreate the behavior easiest by using adb to jump the apps processor to bootloader and waiting for a minute or so before issuing the fastboot continue command. That said, I also have seen the behavior just after rebooting the processor a few times.

      int px4_clock_gettime(clockid_t clk_id, struct timespec *tp)
      {
      #if defined(ENABLE_LOCKSTEP_SCHEDULER)
      
      	if (clk_id == CLOCK_MONOTONIC) {
      		abstime_to_ts(tp, lockstep_scheduler.get_absolute_time());
      		return 0;
      	}
      
      #endif // defined(ENABLE_LOCKSTEP_SCHEDULER)
      	int rv = system_clock_gettime(clk_id, tp);
      
      #if PX4_SOC_ARCH_ID == PX4_SOC_ARCH_ID_VOXL2
      	hrt_abstime temp_abstime = ts_to_abstime(tp);
      	int apps_time_offset = fc_sensor_get_time_offset();
      
      	if (apps_time_offset < 0) {
      		hrt_abstime temp_offset = -apps_time_offset;
      
      		if (temp_offset >= temp_abstime) { temp_abstime = 0; }
      
      		else { temp_abstime -= temp_offset; }
      
      	} else {
      		temp_abstime += (hrt_abstime) apps_time_offset;
      	}
      
      	tp->tv_sec = temp_abstime / 1000000;
      	tp->tv_nsec = (temp_abstime % 1000000) * 1000;
      #endif
      
      	return rv;
      }
      
      posted in Ask your questions right here!
      N
      necurran
    • fc_sensor_get_time_offset functionality

      Is there any documentation about how the fc_sensor_get_time_offset function in libfc-sensor works? Is it expected that this synchronization method would continue to work upon rebooting the apps processor with reboot? How long does it take for the synchronization to take effect?

      posted in Ask your questions right here!
      N
      necurran