pros icon indicating copy to clipboard operation
pros copied to clipboard

✨ Expose VEXos' time and date functions

Open baylessj opened this issue 5 years ago • 12 comments

Summary:

Adds functionality for retrieving the Date and Time stored in VEXos.

Motivation:

I'm working on setting up a logging utility for the BLRS robots and discovered that it would be helpful to set the log file's name as the current date and time to distinguish between the logs more easily.

Test Plan:

pros::date_s_t d = pros::get_date();
pros::time_s_t t = pros::get_time();
printf("%d %d %d %d %d %d %d\n", d.year, d.month, d.day, t.hour, t.min, t.sec, t.sec_hund);
d = pros::c::get_date();
t = pros::c::get_time();
printf("%d %d %d %d %d %d %d\n", d.year, d.month, d.day, t.hour, t.min, t.sec, t.sec_hund);
  • [x] Compiles
  • [x] Run test code on a V5 I printed the output from the functions and got 0:0:0 for time and 11/16/2016 for the date every time.
  • [ ] Get accurate data from date/time functions

baylessj avatar Mar 03 '19 18:03 baylessj

I think there are some newlib stubs we can implement while we're at it. The added bonus is that functions like time(2) are now implemented and I'm fairly certain that some functions from std::chrono will come for free by adding this function.

The function is _gettimeofday(struct timeval *tv, struct timezone *tz). We can ignore tz since it's deprecated. Just need to fill

struct timeval {
    time_t      tv_sec;     /* seconds */
    suseconds_t tv_usec;    /* microseconds */
};

should be straightforward math to convert year/month/day/hours/minutes to seconds since 1970-01-01 00:00:00 (epoch). VEX seems to be nice enough to have given a different epoch year smh but we just need to add 10.

Won't be able to get microsecond precision, only millisecond precision but that's :ok:

edjubuh avatar Mar 03 '19 20:03 edjubuh

I think there are some newlib stubs we can implement while we're at it.

Are you saying this in addition to the "raw" passthrough functions to vexOS? Or instead of those?

HotelCalifornia avatar Mar 04 '19 03:03 HotelCalifornia

Read back through the SDK documentation a bit ago and discovered that these functions have not been implemented in the SDK yet, and there's no real indication of when they will be implemented. Not sure if/when that will happen, so there won't be any more progress with this PR until then.

baylessj avatar Apr 28 '19 19:04 baylessj

I think there are some newlib stubs we can implement while we're at it. The added bonus is that functions like time(2) are now implemented and I'm fairly certain that some functions from std::chrono will come for free by adding this function.

The function is _gettimeofday(struct timeval *tv, struct timezone *tz). We can ignore tz since it's deprecated. Just need to fill

struct timeval {
    time_t      tv_sec;     /* seconds */
    suseconds_t tv_usec;    /* microseconds */
};

should be straightforward math to convert year/month/day/hours/minutes to seconds since 1970-01-01 00:00:00 (epoch). VEX seems to be nice enough to have given a different epoch year smh but we just need to add 10.

Won't be able to get microsecond precision, only millisecond precision but that's

Instead of _gettimeofday I think we can implement clock_gettime(clockid_t clk_id, struct timespec* t) :

Sufficiently recent versions of GNU libc and the Linux kernel support the following clocks:

CLOCK_REALTIME System-wide realtime clock. Setting this clock requires appropriate privileges. CLOCK_MONOTONIC Clock that cannot be set and represents monotonic time since some unspecified starting point. CLOCK_PROCESS_CPUTIME_ID High-resolution per-process timer from the CPU. CLOCK_THREAD_CPUTIME_ID Thread-specific CPU-time clock.

We'd want to just handle CLOCK_MONOTONIC (and maybe CLOCK_PROCESS_CPUTIME_ID CLOCK_THREAD_CPUTIME_ID)-- others can just set errno to EINVAL.

Why CLOCK_MONOTONIC? Because that's what std::chrono::steady_clock calls to get its time (also pros::millis is a monotonic clock).

How would CLOCK_PROCESS_CPUTIME_ID or CLOCK_THREAD_CPUTIME_ID work? ~We'd want to add another TLSP and set the conter in each task to zero on creation, then increment it on each clock tick (hmm this sounds suspiciously familiar to CS 354 Lab 3... @xrex110).~ Actually now that I think about it, this is already stored on the task's control block as ulRunTimeCounter. I don't think std::chrono has interfaces for this so it's a bit lower priority but it would be nice to have.

HotelCalifornia avatar Mar 15 '20 23:03 HotelCalifornia

Is it possible to implement the newlib stubs without an RTC of any sort on the brain? Last I heard, there isn't the hardware to support time and date functions...

baylessj avatar Mar 16 '20 00:03 baylessj

There are a lot of times where the brain wouldn't have power, so any clock with a non-local frame of reference can't really be implemented. The ones alex was talking about can just be the output of a timer we get from VexOS, since they only care about the time period.

nathan-moore avatar Mar 16 '20 02:03 nathan-moore

Yeah, like Nathan said: Linux and friends also provide ways to get system time since boot in milliseconds (that's the CLOCK_MONOTONIC thing or std::chrono::steady_clock), and the other two I mentioned are computed by the scheduler.

Also if we want to go for POSIX compliance too, there are symbols we can define

HotelCalifornia avatar Mar 16 '20 03:03 HotelCalifornia

Read back through the SDK documentation a bit ago and discovered that these functions have not been implemented in the SDK yet, and there's no real indication of when they will be implemented. Not sure if/when that will happen, so there won't be any more progress with this PR until then.

Yeah, and even if the LPC824 CM0 on the brain has a RTC on it, I'm not sure VEX would spend the time to implement it. I honestly think we should change the goal of this PR to be more POSIX compliant in the realm of time related functions (or at the very least rename the PR to be less confusing for anybody looking at it). It also must be noted that the microseconds since the program started was also exposed in an earlier PR at this point in the form of pros::micros.

WillXuCodes avatar Jan 03 '22 22:01 WillXuCodes

It does appear that with vexos 1.1.1 and the new field control, date/time is automatically set to match real world time in VEXos. https://www.vexforum.com/t/new-field-control-sytem-for-vex-worlds-2022/100989/49 Not sure if the aforementioned SDK functions have been updated to actually use this time though.

cgjeffries avatar Apr 11 '22 18:04 cgjeffries

Finished, the robot now displays an approximated time based off of a compiled timestamp and how long the program has been running. This was tested with several time zones.

Time-Robot Time-Terminal

Richard-Stump avatar Aug 26 '22 21:08 Richard-Stump

Hi, I'm from Raider Robotics, and I'm working on a port of micro-ROS to the V5 Brain that I hope to release in the near future. micro-ROS has a dependency on clock_gettime for timed callbacks and exchanging messages with a ROS 2 device, among other reasons. Browsing the code, micro-ROS appears to require CLOCK_MONOTONIC and CLOCK_REALTIME to function correctly. So far, I've gotten it to publish messages to the ROS 2 network by, among other things, partially implementing clock_gettime. Below is my implementation (a simplified and adapted version of this), though it only handles the CLOCK_MONOTONIC case.

#include <sys/time.h>
#include "api.h"
int clock_gettime(clockid_t unused, struct timespec *tp)
{
    (void)unused;

    uint64_t m = micros();

    tp->tv_sec = m / 1000000;
    tp->tv_nsec = (m % 1000000) * 1000;

    return 0;
}

Currently, I believe this PR will cause micro-ROS to crash, as calling clock_gettime with CLOCK_MONOTONIC will result in an error and a return value of -1, as will calling clock_gettime with CLOCK_REALTIME while not connected to the new field system. I can work around the latter (by only running the code while connected to the field), but not the former. Would it be possible to at least implement CLOCK_MONOTONIC before this gets merged? If my above code isn't flawed, it should be as simple as that. As for CLOCK_REALTIME without being connected to the field, I wonder it would be possible to get the time using an external RTC, or, in my case, from the ROS 2 device I'm communicating with. If so, it would be great if clock_settime were also implemented, even if in a future PR.

I'm really excited to see that CLOCK_REALTIME can be implemented with VEX's new field system, as I'm having issues with micro-ROS's Executor system that might be fixed with a working CLOCK_REALTIME implementation. If the above issues are fixed, this could really help.

Thanks!

sb-msoe avatar Aug 27 '22 23:08 sb-msoe

Hi, I'm from Raider Robotics, and I'm working on a port of micro-ROS to the V5 Brain that I hope to release in the near future. micro-ROS has a dependency on clock_gettime for timed callbacks and exchanging messages with a ROS 2 device, among other reasons. Browsing the code, micro-ROS appears to require CLOCK_MONOTONIC and CLOCK_REALTIME to function correctly. So far, I've gotten it to publish messages to the ROS 2 network by, among other things, partially implementing clock_gettime. Below is my implementation (a simplified and adapted version of this), though it only handles the CLOCK_MONOTONIC case.

#include <sys/time.h>
#include "api.h"
int clock_gettime(clockid_t unused, struct timespec *tp)
{
    (void)unused;

    uint64_t m = micros();

    tp->tv_sec = m / 1000000;
    tp->tv_nsec = (m % 1000000) * 1000;

    return 0;
}

Currently, I believe this PR will cause micro-ROS to crash, as calling clock_gettime with CLOCK_MONOTONIC will result in an error and a return value of -1, as will calling clock_gettime with CLOCK_REALTIME while not connected to the new field system. I can work around the latter (by only running the code while connected to the field), but not the former. Would it be possible to at least implement CLOCK_MONOTONIC before this gets merged? If my above code isn't flawed, it should be as simple as that. As for CLOCK_REALTIME without being connected to the field, I wonder it would be possible to get the time using an external RTC, or, in my case, from the ROS 2 device I'm communicating with. If so, it would be great if clock_settime were also implemented, even if in a future PR.

I'm really excited to see that CLOCK_REALTIME can be implemented with VEX's new field system, as I'm having issues with micro-ROS's Executor system that might be fixed with a working CLOCK_REALTIME implementation. If the above issues are fixed, this could really help.

Thanks!

Hi MSOE,

Thanks for the heads up, I'm willing to delay this until 3.7.1 to get CLOCK_MONOTONIC. Glad to see you guys on here and checking in w/ development.

Keep in touch on the midwest discord!

-Will

WillXuCodes avatar Aug 28 '22 06:08 WillXuCodes

I added/fixed the things requested and tested it on real hardware:

  • CLOCK_REALTIME works properly from the compiled timestamp
  • CLOCK_REALTIME can be set with clock_settime(). This correctly changes the the time to the time in GDT.
  • CLOCK_MONOTONIC is now available and correctly counts the number of seconds and microseconds. We do not have a fine enough clock to count nanoseconds like struct timespec has.

image

Richard-Stump avatar Oct 15 '22 20:10 Richard-Stump