https://cyber-rt.readthedocs.io/en/latest/CyberRT_Python_API.html
https://cyber-rt.readthedocs.io/en/latest/api/pythonapi.html

1. 背景

Cyber RT 核心代码是由 C++ 开发,同时为了方便开发者,提供了 Python 接口。

2. Cyber RT Python 接口实现思路

Cyber RT Python 接口的实现思路是在 Cyber RT C++ 实现的基础上,做了一层 Python 的封装,由 Python 来调用 C++ 的实现函数。Cyber RTPython Wrapper 的实现没有使用 swig 等第三方工具,完全自主实现,以此保证代码的高可维护性和可读性。

3. 主要接口

目前提供的主要接口包括:

  • channel 读、写
  • server/client 通信
  • record 信息查询
  • record 文件读、写
  • Time/Duration/Rate 时间操作
  • Timer 定时器

3.1 Channel 读写接口

使用步骤是:

  1. 首先创建 Node;
  2. 创建对应的 readerwriter
  3. 如果是向 channel 写数据,调用 writerwrite 接口;
  4. 如果是从 channel 读数据,调用 nodespin,并在回调函数 callback 中对消息进行处理;

接口定义如下:

class Node:"""Class for Cyber RT Node wrapper."""def create_writer(self, name, data_type, qos_depth=1):"""create a topic writer for send message to topic.@param self@param name str: topic name@param data_type proto: message class for serialization"""def create_reader(self, name, data_type, callback, args=None):"""create a topic reader for receive message from topic.@param self@param name str: topic name@param data_type proto: message class for serialization@callback fn: function to call (fn(data)) when data isreceived. If args is set, the function mustaccept the args as a second argument,i.e. fn(data, args)@args any: additional arguments to pass to the callback"""def create_client(self, name, request_data_type, response_data_type):""""""def create_service(self, name, req_data_type, res_data_type, callback, args=None):def spin(self):"""spin in wait and process message.@param self"""class Writer(object):"""Class for Cyber RT writer wrapper."""def write(self, data):"""writer msg string"""

3.2 Record 接口

Record 读的操作是:

  1. 创建一个 RecordReader;
  2. Record 进行迭代读;

Record 写的操作是:

  1. 创建一个 RecordReader;
  2. Record 进行写消息;

接口定义如下:

class RecordReader(object):"""Class for Cyber RT RecordReader wrapper."""def read_messages(self, start_time=0, end_time=18446744073709551615):"""read message from bag file.@param self@param start_time:@param end_time:@return: generator of (message, data_type, timestamp)"""def get_messagenumber(self, channel_name):"""return message count."""def get_messagetype(self, channel_name):"""return message type."""def get_protodesc(self, channel_name):"""return message protodesc."""def get_headerstring(self):"""return message header string."""def reset(self):"""return reset."""return _Cyber_RECORD.PyRecordReader_Reset(self.record_reader)def get_channellist(self):"""return channel list."""return _Cyber_RECORD.PyRecordReader_GetChannelList(self.record_reader)class RecordWriter(object):"""Class for Cyber RT RecordWriter wrapper."""def open(self, path):"""open record file for write."""def write_channel(self, channel_name, type_name, proto_desc):"""writer channel by channelname,typename,protodesc"""def write_message(self, channel_name, data, time, raw = True):"""writer msg:channelname,data,time,is data raw"""def set_size_fileseg(self, size_kilobytes):"""return filesegment size."""def set_intervaltime_fileseg(self, time_sec):"""return file interval time."""def get_messagenumber(self, channel_name):"""return message count."""def get_messagetype(self, channel_name):"""return message type."""def get_protodesc(self, channel_name):"""return message protodesc."""

3.3 Time 接口

class Time(object):@staticmethoddef now():time_now = Time(_CYBER_TIME.PyTime_now())return time_now@staticmethoddef mono_time():mono_time = Time(_CYBER_TIME.PyTime_mono_time())return mono_timedef to_sec(self):return _CYBER_TIME.PyTime_to_sec(self.time)def to_nsec(self):return _CYBER_TIME.PyTime_to_nsec(self.time)def sleep_until(self, nanoseconds):return _CYBER_TIME.PyTime_sleep_until(self.time, nanoseconds)

3.4 Timer 接口


class Timer(object):def set_option(self, period, callback, oneshot=0):'''period The period of the timer, unit is mscallback The tasks that the timer needs to performoneshot 1: perform the callback only after the first timing cycle0:perform the callback every timed period'''def start(self):def stop(self):

4. 例子

4.1 读 channel (参见 cyber/python/cyber_py3/examples/listener.py)

"""Module for example of listener."""
from cyber.python.cyber_py3 import cyber
from cyber.proto.unit_test_pb2 import ChatterBenchmarkdef callback(data):"""Reader message callback."""print("=" * 80)print("py:reader callback msg->:")print(data)print("=" * 80)def test_listener_class():"""Reader message."""print("=" * 120)test_node = cyber.Node("listener")test_node.create_reader("channel/chatter", ChatterBenchmark, callback)test_node.spin()if __name__ == '__main__':cyber.init()test_listener_class()cyber.shutdown()

apollo 镜像中执行命令

export PYTHONPATH=/apollo/bazel-bin/cyber/python/internal:/apollo:/apollo/cyber/proto

/apollo/cyber 目录下执行

python -m grpc_tools.protoc -I=./proto --python_out=./proto --grpc_python_out=./proto  ./proto/unit_test.proto

用于生成以下两个文件 unit_test_pb2.pyunit_test_pb2_grpc.py

4.2 写 channel(参见 cyber/python/cyber_py3/examples/talker.py)

"""Module for example of talker."""
import timefrom cyber.python.cyber_py3 import cyber
from cyber.proto.unit_test_pb2 import ChatterBenchmarkdef test_talker_class():"""Test talker."""msg = ChatterBenchmark()msg.content = "py:talker:send Alex!"msg.stamp = 9999msg.seq = 0print(msg)test_node = cyber.Node("node_name1")g_count = 1writer = test_node.create_writer("channel/chatter", ChatterBenchmark, 6)while not cyber.is_shutdown():time.sleep(1)g_count = g_count + 1msg.seq = g_countmsg.content = "I am python talker."print("=" * 80)print("write msg -> %s" % msg)writer.write(msg)if __name__ == '__main__':cyber.init("talker_sample")test_talker_class()cyber.shutdown()

分别执行

python cyber/python/cyber_py3/examples/listener.py

python cyber/python/cyber_py3/examples/talker.py

listener.py 打印如下:

========================================================================================================================
================================================================================
py:reader callback msg->:
stamp: 9999
seq: 2
content: "I am python talker."================================================================================
================================================================================
py:reader callback msg->:
stamp: 9999
seq: 3
content: "I am python talker."================================================================================

talker.py 打印如下:

stamp: 9999
seq: 0
content: "py:talker:send Alex!"================================================================================
write msg -> stamp: 9999
seq: 2
content: "I am python talker."================================================================================
write msg -> stamp: 9999
seq: 3
content: "I am python talker."================================================================================

4.3 读写消息到 Record 文件(参见 cyber/python/cyber_py3/examples/record.py)

"""
Module for example of record.
Run with:bazel run //cyber/python/cyber_py3/examples:record
"""import timefrom google.protobuf.descriptor_pb2 import FileDescriptorProtofrom cyber.proto.unit_test_pb2 import Chatter
from cyber.python.cyber_py3 import record
from modules.common.util.testdata.simple_pb2 import SimpleMessageMSG_TYPE = "apollo.common.util.test.SimpleMessage"
MSG_TYPE_CHATTER = "apollo.cyber.proto.Chatter"def test_record_writer(writer_path):"""Record writer."""fwriter = record.RecordWriter()fwriter.set_size_fileseg(0)fwriter.set_intervaltime_fileseg(0)if not fwriter.open(writer_path):print('Failed to open record writer!')returnprint('+++ Begin to writer +++')# Writer 2 SimpleMessagemsg = SimpleMessage()msg.text = "AAAAAA"file_desc = msg.DESCRIPTOR.fileproto = FileDescriptorProto()file_desc.CopyToProto(proto)proto.name = file_desc.namedesc_str = proto.SerializeToString()print(msg.DESCRIPTOR.full_name)fwriter.write_channel('simplemsg_channel', msg.DESCRIPTOR.full_name, desc_str)fwriter.write_message('simplemsg_channel', msg, 990, False)fwriter.write_message('simplemsg_channel', msg.SerializeToString(), 991)# Writer 2 Chattermsg = Chatter()msg.timestamp = 99999msg.lidar_timestamp = 100msg.seq = 1file_desc = msg.DESCRIPTOR.fileproto = FileDescriptorProto()file_desc.CopyToProto(proto)proto.name = file_desc.namedesc_str = proto.SerializeToString()print(msg.DESCRIPTOR.full_name)fwriter.write_channel('chatter_a', msg.DESCRIPTOR.full_name, desc_str)fwriter.write_message('chatter_a', msg, 992, False)msg.seq = 2fwriter.write_message("chatter_a", msg.SerializeToString(), 993)fwriter.close()def test_record_reader(reader_path):"""Record reader."""freader = record.RecordReader(reader_path)time.sleep(1)print('+' * 80)print('+++ Begin to read +++')count = 0for channel_name, msg, datatype, timestamp in freader.read_messages():count += 1print('=' * 80)print('read [%d] messages' % count)print('channel_name -> %s' % channel_name)print('msgtime -> %d' % timestamp)print('msgnum -> %d' % freader.get_messagenumber(channel_name))print('msgtype -> %s' % datatype)print('message is -> %s' % msg)print('***After parse(if needed),the message is ->')if datatype == MSG_TYPE:msg_new = SimpleMessage()msg_new.ParseFromString(msg)print(msg_new)elif datatype == MSG_TYPE_CHATTER:msg_new = Chatter()msg_new.ParseFromString(msg)print(msg_new)if __name__ == '__main__':test_record_file = "/tmp/test_writer.record"print('Begin to write record file: {}'.format(test_record_file))test_record_writer(test_record_file)print('Begin to read record file: {}'.format(test_record_file))test_record_reader(test_record_file)

Apollo 笔记(03)— Cyber RT Python 接口(channel 读和写、server/client 通信、record 文件读写信息查询、timer 时间定时器操作)相关推荐

  1. 下列不是python对文件的写操作方法的是_Python—文件读写操作

    初识文件操作 使用open()函数打开一个文件,获取到文件句柄,然后通过文件句柄就可以进行各种各样的操作了,根据打开文件的方式不同能够执行的操作也会有相应的差异. 打开文件的方式: r, w, a, ...

  2. Python文件读写 w+ 与 r+ 到底如何操作

    原文地址:Python中文件读写之 w+ 与 r+ 到底有啥区别? 本文在原文基础上有删改. r 是只读,只能读不能写,这是很明确的: f = open("test.txt", ' ...

  3. 【学习笔记】opencv的python接口 几何变换

    先跑一下示例代码: 平移: import cv2 as cv import numpy as np from matplotlib import pyplot as plt img = cv.imre ...

  4. 【学习笔记】opencv的python接口 轮廓特征值 滚动条控制阈值参数

    滚动条控制阈值和阈值的处理方式 控制thres中的方式和阈值 import cv2img = cv2.imread("p7.jpg") #img = cv2.cvtColor(im ...

  5. 【学习笔记】opencv的python接口 形态学操作 腐蚀 膨胀 通用形态学函数

    腐蚀 img=np.zeros((5,5),np.uint8) img[1:4,1:4]=1 kernel=np.ones((3,1),np.uint8) erosion=cv2.erode(img, ...

  6. python tcp server_python scoket 编程 | tcp server client - 简明教程

    TCP 和 UDP 的区别 这两个协议都是传输层的协议,解决的问题,都是端口与端口的通信问题. TCP 每次建立通信,都需要三次握手,确定双方状态完毕,在发送数据.如果发送的数据出现了异常,TCP 也 ...

  7. Python 下的 tcp server/client 通信

    说明:只做基础,不做延伸,直接上代码 1.源文件 server.py from socket import *server = socket(AF_INET, SOCK_STREAM) server. ...

  8. cmd执行python 环境变量应该怎么写_python怎么运行py文件?.py文件cmd命令方法及环境变量配置教程...

    python是一款应用非常广泛的脚本程序语言,谷歌公司的网页就是用python编写.python在生物信息.统计.网页制作.计算等多个领域都体现出了强大的功能.python和其他脚本语言如java.R ...

  9. 让python飞:形象理解python os模块、内存硬盘、字节字符、文件读写复制

    Day08葫芦娃救爷爷 葫芦娃去救爷爷,在洞口遇到了一个小机器人.它对葫芦娃说,它是这个洞的管家(os模块管理目录和文件),并告诉葫芦娃这个洞的名字叫温豆思洞,简称牛头洞(# print(os.nam ...

最新文章

  1. tensorflow models 工程解析
  2. Android开发-屏幕常亮的方法
  3. linux 模块常用命令
  4. Intel Idea导入eclipse下的web项目并部署到tomcat
  5. U-Boot顶层Makefile分析
  6. C——任意一个偶数分解两个素数
  7. 【数据结构与算法】【算法思想】【算法总结】索引结构
  8. 终端执行php,PHP命令行执行PHP脚本的注意事项总结
  9. 数据结构之树与二叉树的应用:哈夫曼树(最优二叉树)
  10. golang 使用 consul 做服务发现
  11. java md5算法_JAVA实现MD5算法
  12. Testing a React+Redux web application
  13. oracle中date错误,ORA-01830: date format picture ends before converting entire input string
  14. cluster_acc计算
  15. vue-seamless-scroll遇到一些问题
  16. java面试之每天五题
  17. 麒麟AI首席科学家现世
  18. java 编程 网易公开课,java毕业设计_springboot框架的社区居民健康档案管理实现
  19. 手写汉字识别-单个汉字识别-pyqt可视化交互界面-python代码
  20. 【uni-app】textarea中的换行问题

热门文章

  1. 汤姆猫无法访问html,汤姆猫开始,但HTML不加载
  2. centos挂载超过2T的硬盘
  3. MySQL中 delimiter 关键字详解
  4. C++中sln,vcxproj,vcxproj.filters,lib,dll,exe含义
  5. 【React】 10课 react实现QQ聊天框效果
  6. mysql创建数据库的相关命令及步骤
  7. oss服务端签名后直传分析与代码实现
  8. 2023年最强手机远程控制横测:ToDesk、向日葵、Airdroid三款APP免Root版本
  9. 基于PHP的红酒会所销售信息系统
  10. linux lftp rpm,linux-lftp