ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
3

Convert ros time to hours-minutes-seconds string in system timezone in C++?

asked 2019-12-26 10:59:34 -0500

lucasw gravatar image

updated 2019-12-28 09:16:24 -0500

I want to convert ros time stamps out of message headers to std::string in a form like YYYY MM DD HH MM SS.SSS or similar. Optionally not including the year or month or day would be nice.

An example showing converting the stamp to a generic unix time data structure then passing that into a function that can convert from that to a string using a format string would be very useful to have (ros time to time_t to strftime would be nice), also something showing modern C++ and std::chrono.

Ideally a minimum of dependencies (like boost) or blocks of conversion code to cut and paste would be required.

The answer to #q251966 outputs UTC time uses boost and doesn't show any other control over the output format so isn't sufficient.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
3

answered 2019-12-28 10:35:15 -0500

lucasw gravatar image

updated 2019-12-28 10:37:34 -0500

Converting to local timezone, not using boost (and the seconds needs to be capital 'S' for strftime):

   std::string stampToString(const ros::Time& stamp, const std::string format="%Y-%m-%d %H:%M:%S")
   {
      const int output_size = 100;
      char output[output_size];
      std::time_t raw_time = static_cast<time_t>(stamp.sec);
      struct tm* timeinfo = localtime(&raw_time);
      std::strftime(output, output_size, format.c_str(), timeinfo);
      std::stringstream ss; 
      ss << std::setw(9) << std::setfill('0') << stamp.nsec;  
      const size_t fractional_second_digits = 4;
      return std::string(output) + "." + ss.str().substr(0, fractional_second_digits);
    }
edit flag offensive delete link more

Comments

the best one

rjosodtssp gravatar image rjosodtssp  ( 2020-11-18 21:29:04 -0500 )edit
3

answered 2019-12-26 21:10:21 -0500

The way you control the output format of a boost::posix_time object is by constructing a facet with the format flags that you want and apply the facet to a std::stringstream used to generate the string. It will be clearer with an example:

#include <iostream>
#include <locale>
#include <string>
#include <boost/date_time/posix_time/posix_time.hpp>
#include <boost/date_time/posix_time/posix_time_io.hpp>
#include <ros/ros.h>
...
auto current_time = ros::Time::now().toBoost(); //You asked for modern C++, so... there :P
std::stringstream ss;
boost::posix_time::time_facet facet("%Y %m %d %H %M %s");
ss.imbue(std::locale(std::locale::classic(), &facet));
ss << current_time;
ROS_INFO("Current time: %s", ss.str().c_str());

I hope you find this helpful. (Did this on-the-fly, so this code might not compile, but should put you on the right track)

edit flag offensive delete link more

Comments

It compiles but crashes when the locale destructor tries to free facet:

#3  0x00007ffff5cf390a in malloc_printerr (
    str=str@entry=0x7ffff5e1b7a8 "munmap_chunk(): invalid pointer") at malloc.c:5350  
#4  0x00007ffff5cfaecc in munmap_chunk (p=0x7fffffffb040) at malloc.c:2846
#5  __GI___libc_free (mem=0x7fffffffb050) at malloc.c:3117
#6  0x00007ffff6310834 in std::locale::_Impl::~_Impl() ()
   from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#7  0x00007ffff63109e4 in std::locale::~locale() () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6

so this instead:

auto facet = new boost::posix_time::time_facet("%Y %m %d %H %M %s");
ss.imbue(std::locale(std::locale::classic(), facet));

(so it would be better to create facet once and reuse it). https://stackoverflow.com/questions/1...

lucasw gravatar image lucasw  ( 2019-12-28 09:14:42 -0500 )edit

std::locale::classic and std::cout.getloc() are giving me UTC time, if that could be made into local time I'd prefer this answer.

lucasw gravatar image lucasw  ( 2019-12-28 09:52:28 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2019-12-26 10:59:34 -0500

Seen: 4,331 times

Last updated: Dec 28 '19