Skip to content

Latest commit

 

History

History
executable file
·
239 lines (165 loc) · 13.4 KB

Time.md

File metadata and controls

executable file
·
239 lines (165 loc) · 13.4 KB

Time

[!attention]

应留意因类型不同而导致的精度丢失

Clock

如下代码块只适用于

功能 代码块(ROS2)
设置时钟源 rclcpp::Clock ros_clock{RCL_ROS_TIME};
rclcpp::Clock system_clock{RCL_SYSTEM_TIME};
rclcpp::Clock steady_clock{RCL_STEADY_TIME};
from rclpy.clock import Clock, ROSClock
ROSClock()
Clock()

Time

Second to Time

ROS 2 没有将双精度浮点型(以秒为单位)的时间戳转换为 Time 对象的接口,可以先将其转换为 int64(以 ns 为单位)的时间戳,但该接口会丢失精度。

ROS2(C++) ROS(C++)
// 近似替代
rclcpp::Time t(static_cast<int64_t>(seconds * 1e9));
// 秒(double)
ros::Time(double t)
ros::Time().fromSec(double t)
// 秒(int32)+纳秒(unint32)
Time(int32_t seconds, uint32_t nanoseconds)
// 秒(unint32)+纳秒(unint32)
ros::Time(uint32_t _sec, uint32_t _nsec)
// 纳秒(int64)
rclcpp::Time t(int64_t nanoseconds=0);
// 纳秒(uint64)
ros::Time().fromNSec(uint64_t t)
// 自建消息类型
rclcpp::Time(const builtin_interfaces::msg::Time &time_msg)
ROS2(Python) ROS(Python)
TODO // 秒(整型) + 纳秒(整型)
rospy.Time(secs=0, nsecs=1000000)

Time to Second

ROS2(C++) ROS(C++)
// 秒(double)
double timestamp = rclcpp::Time(msg->header.stamp).seconds();
// 秒(double)
double timestamp = msg->header.stamp.toSec();
double timestamp = msg->header.stamp.sec + msg->header.stamp.nsec * 1e-9;
// 纳秒(uint64)
uint64_t rclcpp::Time(msg->header.stamp).nanoseconds();
// 纳秒(uint64)
uint64_t timestamp = msg->header.stamp.toNSec();
ROS2(Python) ROS(Python)
TODO // 秒(浮点数)
timestamp = (msg.header.stamp).secs + (msg.header.stamp).nsecs * 1e-9;

Now

ROS2(C++) ROS(C++)
rclcpp::Time t = now();
rclcpp::Time t = this->now();
rclcpp::Time t = this->get_clock()->now();
ros::Time t = ros::Time::now();
ROS2(Python) ROS(Python)
# 需要 Node 对象
self.get_clock().now();

# 不需要 Node 对象
from rclpy.clock import Clock
time_stamp = Clock().now().to_msg()
// 仅支持整型
rospy.Time(secs=0, nsecs=1000000)

RViz

ROS2 ROS1
context_->getClock()->now(); // 默认是ROS时间
ros::Time::now();
// 没有无参构造函数,近似等价于
rclcpp::Time(std::int64_t(0), RCL_ROS_TIME)
// 默认是ROS时间
ros::Time()

TF

从缓存中获取最新的 TF,具体参考 Here

ROS2(C++) ROS(C++)
tf2::TimePointZero

tf2::TimePoint(std::chrono::milliseconds(0))
ros::Time(0)
rclcpp::Time(0, 0, this->get_clock()->get_clock_type())
rclcpp::Time(0)
ros::Time(0)
// ROS2 内置时间戳类转为 TF 时间戳类
tf2::TimePoint tf2_ros::fromMsg	(const builtin_interfaces::msg::Time & time_msg)

Duration

Second to Duration

ROS2(C++) ROS(C++)
// 秒(int32_t) + 纳秒(uint32_t)
rclcpp::Duration t = rclcpp::Duration(0, 0);
// 秒(int32_t) + 纳秒(int32_t)
Duration (int32_t _sec, int32_t _nsec);
// 秒(double)版本需大于 foxy
rclcpp::Duration d = rclcpp::Duration::from_seconds(0.5);
// 秒(double)
ros::Duration t = ros::Duration(0.5);
// 内置消息类型
Duration (const builtin_interfaces::msg::Duration &duration_msg)
TODO
Duration (rcl_duration_value_t nanoseconds)
Duration (std::chrono::nanoseconds nanoseconds)
TODO
ROS2(Python) ROS(Python)
// 秒
from rclpy.duration import Duration
Duration(seconds=0).to_msg();
// 秒
rospy.Duration(0.02);

Duration to Second

ROS2(C++) ROS(C++)
double seconds = d.seconds(); TODO
rcl_duration_value_t seconds = d.nanoseconds(); TODO
ROS2(Python) ROS(Python)
TODO TODO

Sleep

ROS2(C++) ROS(C++)
#include <chrono>
std::this_thread::sleep_for(pause_aniation_duration_.to_chrono<std::chrono::seconds>());
// 秒
ros::Duration(0.5).sleep();
ROS2(Python) ROS(Python)
使用标准库 // 秒
rospy.sleep(0.5)

Other

ROS2(C++) ROS(C++)
isZero()

Rate and Timer

推荐使用 Timer 来实现特定频率的循环而不是使用 rate 机制

Timer Callback

C++ (ROS 2)

ROS2 的回调函数无形参

timer_ = rclcpp::create_timer(this, get_clock(), period_ns, std::bind(&Node::run, this));

using std::chrono_literals::operator ""ms;
timer_ = rclcpp::create_timer(this, get_clock(), 100ms, std::bind(&Node::timerCallback, this));

timer_period = 0.2  # 单位:秒
self.timer = self.create_timer(timer_period, self.timer_callback)

C++ (ROS)

// 定时器回调函数
ros::Timer timer = nh.createTimer(ros::Duration(1.0 / publish_rate), &onTimer, this);
// 类成员函数,方案一
ros::Timer timer = nh.createTimer(ros::Duration(0.1), &Foo::callback, &foo_object); 
// 类成员函数,方案二
ros::Timer timer = nh.createTimer(ros::Duration(0.1), callback);

// 对应的回调函数需含如下指定形参
void onTimer(const ros::TimerEvent& e);

Python (ROS 2)

ROS 2 没有rospy.Rate(5),只能通过定时器来实现

Python (ROS)

import rospy

rospy.Timer(rospy.Duration(2), on_timer)  # 单位:秒


def on_timer(self, event):
    pass

Usage

🔧 用例 1: 如何将录制传感器的时间作为时钟源给节点使用?

回放rosbag时添加选项--clock来发布/clock主题,ROS client 库则会将此主题作为时钟源提供时间

🔧 用例 2: 让一个节点使用仿真时间源?

设置参数:/use_sim_time=true

(ROS) $ rosparam set /use_sim_time true
🔧 用例 3: 在 /use_sim_clock = True 的情况下依然获取系统时间,而不是仿真时间
ROS(C++) ROS(C++)
ros::WallTime stime;
stime = ros::WallTime::now()
ros::WallDuration duration = ros::WallTime::now() - stime;
// 默认已经是系统时间了
rclcpp::Time t = rclcpp::Clock{RCL_SYSTEM_TIME}.now();

FAQ

问题 1: ROS 中默认使用的时钟源是?

s 根据实验,应该为system clock,即wall clock

问题 2: Field of type 'rclcpp::Duration' has private default constructor 导致无法实例化类

字面意思,rclcpp::Duration 的默认构造函数为私有函数,无法被访问,需使用其他构造函数

private: // 私有成员
  rcl_duration_t rcl_duration_;
  Duration() = default;

Reference

概要 链接
ROS API 文档 TimeDuration
ROS2 API 文档 TimeClockDuration
Design:ROS 2 Clock and Time https://design.ros2.org/articles/clock_and_time.html
ROS Clock https://wiki.ros.org/Clock
TF ROS2