ROS2-013-通信机制补完:时间类 API
简介
假设有一个机器人,在机器人上有一个雷达。该雷达有一相关节点会发布雷达探测到的各种信息,且会被机器人内部一导航模块所属节点订阅并接收。为了减少机器人移动过程中由于通信延迟在路径规划上产生相关误差,当二者进行数据交互时,必然需要保证信息的实时性。
因此我们需要使用 时间类 API,在传输数据时提供相关数据产生时的时间戳使接收方能够进行相关数据时效性的判断。除此之外,雷达坐标变换或多消息融合等也需要该类 API。
类型
时间类 API 一共有以下几种:
- Rate 类
- Time 类
- Duration 类
下面是对这几类的详细说明:
1.Rate 类
在 话题通信的案例中,我们要求话题发布方按照一定的频率发布消息,当时的实现是通过定时器来控制发布频率的。
其实除了定时器之外,ROS2 中还提供了 Rate 类,通过该类对象也可以控制程序的运行频率。
为了使用该类,我们首先需要创建一个对象,该对象需要传入时间间隔或者频率间隔;之后在需要使用时,结合 while 等循环以及 rate.sleep()
函数对程序的运行频率进行控制。
①. 在 rclcpp 中使用 Rate 类
例如,我们需要周期性输出一段文本:----&----
// 1. 包含头文件
#include "rclcpp/rclcpp.hpp"
using namespace std::chrono_literals;
// 3. 定义节点类:
class TImeTestNode : public rclcpp::Node
{
public:
TImeTestNode() : Node("time_test_node_cpp")
{
demo_rate();
return;
};
private:
// Rate 类的使用
void demo_rate()
{
// 1. 创建 Rate 对象
rclcpp::Rate rate1(1000ms); // 方式一
rclcpp::Rate rate2(2.0); // 方式二 (Unit: Hz/s)
// 2. 调用 Rate 的 sleep 函数
while (rclcpp::ok())
{
RCLCPP_INFO(this->get_logger(), "----&----");
// rate1.sleep();
rate2.sleep();
}
}
};
int main(int argc, char **argv)
{
// 2. 初始化 ROS2 客户端
rclcpp::init(argc, argv);
// 4. 调用spin函数,并传入节点对象指针。
rclcpp::spin(std::make_shared<TImeTestNode>());
// 5.释放资源;
rclcpp::shutdown();
return 0;
}
注
为了使用时间单位,记得 using namespace std::chrono_literals;
②. 在 rclpy 中使用 Rate 类
例如,我们需要周期性输出一段文本:----**----
# 1. 导包;
import rclpy
from rclpy.node import Node
import threading
# 3. 定义节点类:
class TImeTestNode(Node):
def __init__(self):
super().__init__("time_test_node_py")
self.demo_rate()
def demo_rate(self):
# 1. 创建 Rate 对象
self.rate = self.create_rate(1.0) # (Unit: Hz/s)
# fake 2. 直接调用 Rate 的 sleep 函数 --会导致程序阻塞
# while rclpy.ok():
# self.get_logger().info("----**----")
# self.rate.sleep()
# 2. 通过子线程调用 Rate 的 sleep 函数(Python 独有)
thread = threading.Thread(target=self.do_rate)
thread.start()
def do_rate(self):
while rclpy.ok():
self.get_logger().info("----**----")
self.rate.sleep()
def main():
# 2. 初始化 ROS2 客户端
rclpy.init()
# 4. 调用spin函数, 并传入节点对象。
rclpy.spin(TImeTestNode())
# 5.释放资源;
rclpy.shutdown()
if __name__ == '__main__':
main()
请注意
在 Python 中,针对 Rate 你需要 创建一个子线程 以调用 Rate 的 sleep 函数。如果直接调用会导致程序阻塞(在本例子中即为:仅输出一行"----**----"而非按照既定频率进行多次输出)
2.Time 类
Time 类的使用较为简单。为了使用该类,我们首先需要创建一个对象,该对象需要传入自定时间;之后在需要使用时,调用其内置函数。也可以通过 节点 获取当前时刻以创建对象。
①. 在 rclcpp 中使用 Time 类
// 1. 包含头文件
#include "rclcpp/rclcpp.hpp"
using namespace std::chrono_literals;
// 3. 定义节点类:
class TImeTestNode : public rclcpp::Node
{
public:
TImeTestNode() : Node("time_test_node_cpp")
{
demo_time();
return;
};
private:
// 演示 Time 的使用
void demo_time()
{
// 1. 创建 Time 对象 -- 自定义时间
rclcpp::Time t1(500000000L); // 传入 纳秒
rclcpp::Time t2(2, 300000000L); // 传入 秒 和 纳秒
// 1. 创建 Time 对象 -- 通过 节点 直接获取
// rclcpp::Time t_now = this->get_clock()->now();
rclcpp::Time t3_now = this->now();
// 2. 调用 Time 的相关函数
RCLCPP_INFO(this->get_logger(), "t1: s = %.2f, ns = %ld", t1.seconds(), t1.nanoseconds());
RCLCPP_INFO(this->get_logger(), "t2: s = %.2f, ns = %ld", t2.seconds(), t2.nanoseconds());
RCLCPP_INFO(this->get_logger(), "t3_now: s = %.2f, ns = %ld", t3_now.seconds(), t3_now.nanoseconds());
}
};
int main(int argc, char **argv)
{
// 2. 初始化 ROS2 客户端
rclcpp::init(argc, argv);
// 4. 调用spin函数,并传入节点对象指针。
rclcpp::spin(std::make_shared<TImeTestNode>());
// 5.释放资源;
rclcpp::shutdown();
return 0;
}
②. 在 rclpy 中使用 Time 类
# 1. 导包;
import rclpy
from rclpy.node import Node
from rclpy.time import Time
# 3. 定义节点类:
class TImeTestNode(Node):
def __init__(self):
super().__init__("time_test_node_py")
self.demo_time()
def demo_time(self):
# 1. 创建 Time 对象 -- 自定义时间
t1 = Time(seconds=2, nanoseconds=500000000)
# 创建 Time 对象 -- 通过 节点 直接获取
t2_now = self.get_clock().now()
# 2. 调用 Time 函数
self.get_logger().info("t1: s = %.2f, ns = %d" % (t1.seconds_nanoseconds()[0], t1.seconds_nanoseconds()[1]))
self.get_logger().info("t2_now: s = %.2f, ns = %d" % (t2_now.seconds_nanoseconds()[0], t2_now.seconds_nanoseconds()[1]))
self.get_logger().info("t2_now using nanoseconds: ns = %d" % (t2_now.nanoseconds))
def main():
# 2. 初始化 ROS2 客户端
rclpy.init()
# 4. 调用spin函数, 并传入节点对象。
rclpy.spin(TImeTestNode())
# 5.释放资源;
rclpy.shutdown()
if __name__ == '__main__':
main()
注
记得 通过 from rclpy.time import Time
进行引用
3.Duration 类
Duration 类的使用与 Time 类 类似。为了使用该类,我们首先需要创建一个对象,该对象需要传入时间;之后在需要使用时,调用其内置函数。
①. 在 rclcpp 中使用 Duration 类
// 1. 包含头文件
#include "rclcpp/rclcpp.hpp"
using namespace std::chrono_literals;
// 3. 定义节点类:
class TImeTestNode : public rclcpp::Node
{
public:
TImeTestNode() : Node("time_test_node_cpp")
{
demo_duration();
return;
};
private:
// 演示 Duration 的使用
void demo_duration()
{
// 1. 创建 Duration 对象
rclcpp::Duration d1(1s);
rclcpp::Duration d2(1, 500000000);
// 1. 调用 Duration 对象 的函数
RCLCPP_INFO(this->get_logger(), "d1: s = %.2f, ns = %ld", d1.seconds(), d1.nanoseconds());
RCLCPP_INFO(this->get_logger(), "d2: s = %.2f, ns = %ld", d2.seconds(), d2.nanoseconds());
}
};
int main(int argc, char **argv)
{
// 2. 初始化 ROS2 客户端
rclcpp::init(argc, argv);
// 4. 调用spin函数,并传入节点对象指针。
rclcpp::spin(std::make_shared<TImeTestNode>());
// 5.释放资源;
rclcpp::shutdown();
return 0;
}
注
记得 using namespace std::chrono_literals;
②. 在 rclpy 中使用 Duration 类
# 1. 导包;
import rclpy
from rclpy.node import Node
from rclpy.duration import Duration
# 3. 定义节点类:
class TImeTestNode(Node):
def __init__(self):
super().__init__("time_test_node_py")
self.demo_duration()
def demo_duration(self):
# 创建 Duration 对象
d1 = Duration(seconds=1, nanoseconds=500000000)
# 2. 调用 Duration 对象 内的相关函数
self.get_logger().info("t1: ns = %d" % (d1.nanoseconds))
def main():
# 2. 初始化 ROS2 客户端
rclpy.init()
# 4. 调用spin函数, 并传入节点对象。
rclpy.spin(TImeTestNode())
# 5.释放资源;
rclpy.shutdown()
if __name__ == '__main__':
main()
注
记得 通过 from rclpy.duration import Duration
进行引用
Time 类 与 Duration 类 之间的异同与其运算
①. 异同
二者只是 API 使用类似,这两个类 有本质区别:
- Time 指的是时间的 时间戳
- Duration 指的是时间的 持续长度
②. 运算
C++
假设有以下变量:
rclcpp::Time t1(1,500000000);
rclcpp::Time t2(10,0);
rclcpp::Duration d1(2,0);
rclcpp::Duration d2(4,0);
则可以使用包括但不限于以下运算方式进行相应计算:
比较:
RCLCPP_INFO(node->get_logger(), "t1 >= t2 ? %d", t1 >= t2); RCLCPP_INFO(node->get_logger(), "t1 < t2 ? %d", t1 < t2); RCLCPP_INFO(node->get_logger(), "d1 >= d2 ? %d", d1 >= d2); RCLCPP_INFO(node->get_logger(), "d1 < d2 ? %d", d1 < d2);
数学运算:
rclcpp::Time t3 = t1 + du1; rclcpp::Time t4 = t2 - du2; rclcpp::Duration d3 = t2 - t1; rclcpp::Duration d4 = d1 * 3.0; rclcpp::Duration d5 = d1 + d2; rclcpp::Duration d6 = d2 - d1;
Python
假设有以下变量:
t1 = Time(seconds = 1);
t2 = Time(seconds = 10);
d1 = Duration(seconds = 2);
d2 = Duration(seconds = 4);
则可以使用包括但不限于以下运算方式进行相应计算:
比较:
node.get_logger().info("t1 >= t2 ? %d" % (t1 >= t2)); node.get_logger().info("t1 < t2 ? %d" % (t1 < t2)); node.get_logger().info("d1 >= d2 ? %d" % (d1 >= d2)); node.get_logger().info("d1 < d2 ? %d" % (d1 < d2));
数学运算:
t3 = t1 + du1; t4 = t2 - du2; d3 = t2 - t1; d4 = d1 * 3.0; d5 = d1 + d2; d6 = d2 - d1;
总结
本小节针对时间类 API,包括 Rate 类、Time 类 和 Duration 类 三大类 API 分别进行了相应的阐述。在节点间通信时,该类 API 将会有较大用处。