Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor: sparate ros2 dependency in aimrt_py #117

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ __pycache__/
*_pb2_grpc.py
*_aimrt_rpc_ros2.py
log/
test_log/
tmp/

compile_commands.json
350 changes: 0 additions & 350 deletions src/examples/py/py_tests.py

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ def EventHandle(ctx_ref: aimrt_py.ContextRef, msg: RosTestMsg):
nonlocal count
count += 1
aimrt_py.info(module_handle.GetLogger(),
f"Get new ros2 message, ctx: {ctx_ref.ToString()}, data: {msg.data}, count: {count}")
f"Get new ros2 message, data: {msg.data}, ctx: {ctx_ref.ToString()}, count: {count}")

aimrt_py.Subscribe(subscriber, RosTestMsg, EventHandle)

Expand Down
4 changes: 2 additions & 2 deletions src/examples/py/ros2_rpc/examples_py_ros2_rpc_server_app.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,9 @@ def RosTestRpc(self, ctx_ref, req):
RosTestRpcImpl.PrintMetaInfo(self.logger, ctx_ref)
aimrt_py.info(self.logger,
f"Server handle new rpc call. "
f"context: {ctx_ref.ToString()}, "
f"req: {req}, "
f"return rsp: {rsp}")
f"return rsp: {rsp}, "
f"context: {ctx_ref.ToString()}")

return aimrt_py.RpcStatus(), rsp

Expand Down
41 changes: 37 additions & 4 deletions src/examples/utils/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -57,14 +57,47 @@ class TestResult:
]

# Default expected outputs for pb_chn_python
default_pb_chn_sub_expected_outputs_python = ["Get new pb event, data: {", '"msg": "example msg"', '"num": 123456']
default_pb_chn_pub_expected_outputs_python = ["Publish new pb event, data: {", '"msg": "example msg"', '"num": 123456']
default_pb_chn_sub_expected_outputs_python = [
"Get new pb event, ctx: Subscriber context, meta:",
"Get new pb event, ctx: Subscriber context, meta:",
"Get new pb event, ctx: Subscriber context, meta:",
"Get new pb event, ctx: Subscriber context, meta:",
]
default_pb_chn_pub_expected_outputs_python = [
"Publish new pb event, data: {",
"Publish new pb event, data: {",
"Publish new pb event, data: {",
"Publish new pb event, data: {",
]

# Default expected outputs for ros2_chn_python
default_ros2_chn_sub_expected_outputs_python = [
"Get new ros2 message, data:",
"Get new ros2 message, data:",
"Get new ros2 message, data:",
"Get new ros2 message, data:",
]
default_ros2_chn_pub_expected_outputs_python = [
R"Publish new ros2 message, data: [b'\x01', b'\x02', b'\x03', b'\x04']",
R"Publish new ros2 message, data: [b'\x05', b'\x06', b'\x07', b'\x08']",
R"Publish new ros2 message, data: [b'\t', b'\n', b'\x0b', b'\x0c']",
R"Publish new ros2 message, data: [b'\r', b'\x0e', b'\x0f', b'\x10']",
]

# Default expected outputs for pb_rpc_python
default_pb_rpc_srv_expected_outputs_python = ["Server handle new rpc call."]
default_pb_rpc_cli_expected_outputs_python = ["Call rpc done, status: suc, code 0, msg: OK"]

# Default expected outputs for ros2_rpc_python
default_ros2_rpc_srv_expected_outputs_python = [
R"Server handle new rpc call. "
R"req: example_ros2.srv.RosTestRpc_Request(data=[b'H', b'e', b'l', b'l', b'o', b' ', b'A', b'i', b'm', b'R', b'T', b'!']), "
R"return rsp: example_ros2.srv.RosTestRpc_Response(code=1000)"]
default_ros2_rpc_cli_expected_outputs_python = [
R"Call rpc done, status: suc, code 0, msg: OK, "
R"req: example_ros2.srv.RosTestRpc_Request(data=[b'H', b'e', b'l', b'l', b'o', b' ', b'A', b'i', b'm', b'R', b'T', b'!']), "
R"rsp: example_ros2.srv.RosTestRpc_Response(code=1000)"]

# Default exit string
default_exit_string = "AimRT exit."

Expand Down Expand Up @@ -95,9 +128,9 @@ def upwards_find_aim_directory(aim: str = "build", start_directory: str = os.get


# Default build path
defualt_build_path = upwards_find_aim_directory()
default_build_path = upwards_find_aim_directory()

# Default py_path
py_cwd = defualt_build_path + "/../src/examples/py"
py_cwd = default_build_path + "/../src/examples/py"

default_save_path = os.path.join(os.getcwd(), "test_log")
78 changes: 73 additions & 5 deletions src/examples/utils/example_items.py
Original file line number Diff line number Diff line change
Expand Up @@ -617,7 +617,7 @@
default_pb_rpc_srv_expected_outputs_python,
default_pb_rpc_cli_expected_outputs_python,
],
"tags": ["all", "python", "http", "pb", "rpc"],
"tags": ["all", "python", "plugins", "net_plugin", "http", "pb", "rpc"],
"cwd": py_cwd + "/pb_rpc",
"limit": "port:50080",
},
Expand All @@ -631,7 +631,7 @@
default_pb_rpc_srv_expected_outputs_python,
default_pb_rpc_cli_expected_outputs_python,
],
"tags": ["all", "python", "grpc", "pb", "rpc"],
"tags": ["all", "python", "plugins", "grpc_plugin", "pb", "rpc"],
"cwd": py_cwd + "/pb_rpc",
"limit": "port:50050",
},
Expand All @@ -645,7 +645,7 @@
default_pb_rpc_srv_expected_outputs_python,
default_pb_rpc_cli_expected_outputs_python,
],
"tags": ["all", "python", "ros_pluginc", "pb", "rpc"],
"tags": ["all", "python", "plugins", "ros2_plugin", "pb", "rpc"],
"cwd": py_cwd + "/pb_rpc",
},
# ---------------------------------python_http_pb_chn----------------------------------------
Expand All @@ -658,7 +658,7 @@
default_pb_chn_sub_expected_outputs_python,
default_pb_chn_pub_expected_outputs_python,
],
"tags": ["all", "python", "http", "pb", "chn"],
"tags": ["all", "python", "plugins", "net_plugin", "http", "pb", "chn"],
"cwd": py_cwd + "/pb_chn",
"limit": "port:50080",
},
Expand All @@ -672,7 +672,7 @@
default_pb_chn_sub_expected_outputs_python,
default_pb_chn_pub_expected_outputs_python,
],
"tags": ["all", "python", "ros2_plugin", "pb", "chn"],
"tags": ["all", "python", "plugins", "ros2_plugin", "pb", "chn"],
"cwd": py_cwd + "/pb_chn",
},
# ---------------------------------python_parameter----------------------------------------
Expand All @@ -693,4 +693,72 @@
"tags": ["all", "python", "parameter"],
"cwd": py_cwd + "/parameter",
},
# ---------------------------------python_http_ros2_chn----------------------------------------
{
"script_path": [
"./start_examples_py_ros2_chn_http_sub.sh",
"./start_examples_py_ros2_chn_http_pub.sh",
],
"expected_outputs": [
default_ros2_chn_sub_expected_outputs_python,
default_ros2_chn_pub_expected_outputs_python,
],
"tags": ["all", "python", "plugins", "net_plugin", "http", "ros2", "chn"],
"cwd": py_cwd + "/ros2_chn",
"limit": "port:50080",
},
# ---------------------------------python_ros2_ros2_chn----------------------------------------
{
"script_path": [
"./start_examples_py_ros2_chn_ros2_sub.sh",
"./start_examples_py_ros2_chn_ros2_pub.sh",
],
"expected_outputs": [
default_ros2_chn_sub_expected_outputs_python,
default_ros2_chn_pub_expected_outputs_python,
],
"tags": ["all", "python", "plugins", "ros2_plugin", "ros2", "chn"],
"cwd": py_cwd + "/ros2_chn",
},
# ---------------------------------python_http_ros2_rpc----------------------------------------
{
"script_path": [
"./start_examples_py_ros2_rpc_http_server.sh",
"./start_examples_py_ros2_rpc_http_client.sh",
],
"expected_outputs": [
default_ros2_rpc_srv_expected_outputs_python,
default_ros2_rpc_cli_expected_outputs_python,
],
"tags": ["all", "python", "plugins", "net_plugin", "http", "ros2", "rpc"],
"cwd": py_cwd + "/ros2_rpc",
"limit": "port:50080",
},
# ---------------------------------python_grpc_ros2_rpc----------------------------------------
{
"script_path": [
"./start_examples_py_ros2_rpc_grpc_server.sh",
"./start_examples_py_ros2_rpc_grpc_client.sh",
],
"expected_outputs": [
default_ros2_rpc_srv_expected_outputs_python,
default_ros2_rpc_cli_expected_outputs_python,
],
"tags": ["all", "python", "plugins", "grpc_plugin", "ros2", "rpc"],
"cwd": py_cwd + "/ros2_rpc",
"limit": "port:50050",
},
# ---------------------------------python_ros2_ros2_rpc----------------------------------------
{
"script_path": [
"./start_examples_py_ros2_rpc_ros2_server.sh",
"./start_examples_py_ros2_rpc_ros2_client.sh",
],
"expected_outputs": [
default_ros2_rpc_srv_expected_outputs_python,
default_ros2_rpc_cli_expected_outputs_python,
],
"tags": ["all", "python", "plugins", "ros2_plugin", "ros2", "rpc"],
"cwd": py_cwd + "/ros2_rpc",
},
]
19 changes: 12 additions & 7 deletions src/examples/utils/run_all_example.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,17 +2,18 @@
# All rights reserved.

import argparse
from concurrent.futures import ThreadPoolExecutor, as_completed
from datetime import datetime
from example_items import *
from multiprocessing import Process, Queue
import signal
import subprocess
import sys
import tempfile
import threading
import time
from concurrent.futures import ThreadPoolExecutor, as_completed
from datetime import datetime
from multiprocessing import Process, Queue
from typing import Dict, List, Tuple
import sys

from example_items import *


class ExampleRunner:
Expand All @@ -32,7 +33,7 @@ def __init__(self):
self.check_and_create_directory(self.args.save) # todo ...
subprocess.run(
["pip3", "install", "./aimrt_py_pkg/dist/aimrt_py-0.9.0-cp310-cp310-linux_x86_64.whl", "--force-reinstall"],
cwd=defualt_build_path,
cwd=default_build_path,
)
subprocess.run(
["bash", os.path.join("build_examples_py_pb_rpc.sh")],
Expand All @@ -42,6 +43,10 @@ def __init__(self):
["bash", os.path.join("build_examples_py_pb_chn.sh")],
cwd=os.path.join(py_cwd, "pb_chn"),
)
subprocess.run(
["bash", os.path.join("build_examples_py_ros2_rpc.sh")],
cwd=os.path.join(py_cwd, "ros2_rpc"),
)

def check_and_create_directory(self, test_log_save_path: str) -> None:
if test_log_save_path and not os.path.exists(test_log_save_path):
Expand Down Expand Up @@ -155,7 +160,7 @@ def check_item_format(self, item: dict) -> None:

# add default parameters:build directory path, if not exist
if "cwd" not in item:
item["cwd"] = defualt_build_path
item["cwd"] = default_build_path

if "limit" in item and item["limit"] not in self.lock_dict:
self.lock_dict[item["limit"]] = threading.Lock()
Expand Down
2 changes: 1 addition & 1 deletion src/examples/utils/run_all_example.sh
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
# -s <string> : fault test log output directory (default: "build/test_log")
# -t <string1> <string2> ... : test tags, with logic is "AND" (default: "all")
# -i <string1> <string2> ... : ignore test tags, with logic is "OR" (default: None)
# -p : print test log to console (default: False), we don't suggest to use this option with n > 1
# -p : print test log to console (default: False), we don't suggest to use this option with n > 1

source ../../../build/install/share/ros2_plugin_proto/local_setup.bash

Expand Down
28 changes: 16 additions & 12 deletions src/runtime/python_runtime/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,13 +13,9 @@ set(CUR_TARGET_NAME ${CUR_SUPERIOR_NAMESPACE_UNDERLINE}_${CUR_DIR})
set(CUR_TARGET_ALIAS_NAME ${CUR_SUPERIOR_NAMESPACE}::${CUR_DIR})

# Set file collection
file(GLOB_RECURSE src CONFIGURE_DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/*.cc)
file(GLOB_RECURSE src CONFIGURE_DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/python_runtime_main.cc)
file(GLOB_RECURSE py_files CONFIGURE_DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/*.py)
file(GLOB_RECURSE ros2_files CONFIGURE_DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/ros2_type_support_utils.cc)

if(NOT AIMRT_BUILD_WITH_ROS2)
list(REMOVE_ITEM src ${ros2_files})
endif()
file(GLOB_RECURSE ros2_files CONFIGURE_DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/ros2_type_support_utils.cc ${CMAKE_CURRENT_SOURCE_DIR}/python_runtime_ros2.cc)

# Add target
pybind11_add_module(${CUR_TARGET_NAME} SHARED)
Expand All @@ -33,13 +29,21 @@ target_link_libraries(
${CUR_TARGET_NAME}
PRIVATE $<LINK_LIBRARY:WHOLE_ARCHIVE,aimrt::runtime::core>)

# Link ros2 interface if building with ros2
if(AIMRT_BUILD_WITH_ROS2)
target_link_libraries(${CUR_TARGET_NAME} PRIVATE aimrt::interface::aimrt_module_ros2_interface)
target_compile_definitions(${CUR_TARGET_NAME} PRIVATE AIMRT_BUILD_WITH_ROS2)
endif()

# Set misc of target
set_target_properties(${CUR_TARGET_NAME} PROPERTIES OUTPUT_NAME "aimrt_python_runtime")

set_property(TARGET ${CUR_TARGET_NAME} PROPERTY PY_FILES ${py_files})

if(AIMRT_BUILD_WITH_ROS2)
pybind11_add_module(${CUR_TARGET_NAME}_ros2 SHARED)
add_library(${CUR_TARGET_ALIAS_NAME}_ros2 ALIAS ${CUR_TARGET_NAME}_ros2)

target_sources(${CUR_TARGET_NAME}_ros2 PRIVATE ${ros2_files})

target_link_libraries(
${CUR_TARGET_NAME}_ros2 #
PRIVATE $<LINK_LIBRARY:WHOLE_ARCHIVE,aimrt::runtime::core> #
aimrt::interface::aimrt_module_ros2_interface)

set_target_properties(${CUR_TARGET_NAME}_ros2 PROPERTIES OUTPUT_NAME "aimrt_python_runtime_ros2")
endif()
13 changes: 8 additions & 5 deletions src/runtime/python_runtime/aimrt_py_chn.py
Original file line number Diff line number Diff line change
Expand Up @@ -81,10 +81,11 @@ def RegisterPublishType(publisher: aimrt_python_runtime.PublisherRef,
py_pb_ts.SetSerializationTypesSupportedList(["pb", "json"])
return publisher.PbRegisterPublishType(py_pb_ts)
elif check_is_valid_ros2_msg_type(msg_type):
py_ros2_ts = aimrt_python_runtime.PyRos2TypeSupport(msg_type)
from . import aimrt_python_runtime_ros2 as aimrt_py_ros2
py_ros2_ts = aimrt_py_ros2.PyRos2TypeSupport(msg_type)
py_ros2_ts.SetTypeName(GetRos2MessageTypeName(msg_type))
py_ros2_ts.SetSerializationTypesSupportedList(["ros2"])
return publisher.Ros2RegisterPublishType(py_ros2_ts)
return aimrt_py_ros2.Ros2RegisterPublishType(publisher, py_ros2_ts)
else:
raise TypeError(f"Invalid message type: {type(msg_type)}")

Expand Down Expand Up @@ -140,8 +141,9 @@ def Publish(publisher: aimrt_python_runtime.PublisherRef, second, third=None):
serialized_msg = _SerializeProtobufMessage(msg, ctx_ref.GetSerializationType())
publisher.PbPublishWithCtx(GetPbMessageTypeName(msg.__class__), ctx_ref, serialized_msg)
elif message_type == "ros2":
from . import aimrt_python_runtime_ros2 as aimrt_py_ros2
ctx_ref = _CreateContextRef(ctx_or_type, default_serialization_type="ros2")
publisher.Ros2PublishWithCtx(GetRos2MessageTypeName(msg.__class__), ctx_ref, msg)
aimrt_py_ros2.Ros2PublishWithCtx(publisher, GetRos2MessageTypeName(msg.__class__), ctx_ref, msg)


def Subscribe(subscriber: aimrt_python_runtime.SubscriberRef,
Expand Down Expand Up @@ -187,7 +189,8 @@ def handle_callback(ctx_ref: aimrt_python_runtime.ContextRef, msg_buf: bytes):
subscriber.PbSubscribeWithCtx(py_pb_ts, handle_callback)

elif check_is_valid_ros2_msg_type(msg_type):
py_ros2_ts = aimrt_python_runtime.PyRos2TypeSupport(msg_type)
from . import aimrt_python_runtime_ros2 as aimrt_py_ros2
py_ros2_ts = aimrt_py_ros2.PyRos2TypeSupport(msg_type)
py_ros2_ts.SetTypeName(GetRos2MessageTypeName(msg_type))
py_ros2_ts.SetSerializationTypesSupportedList(["ros2"])

Expand All @@ -200,7 +203,7 @@ def ros2_callback_wrapper(ctx_ref: aimrt_python_runtime.ContextRef, msg):
except Exception as e:
print(f"AimRT channel handle get exception, {e}", file=sys.stderr)

subscriber.Ros2SubscribeWithCtx(py_ros2_ts, msg_type, ros2_callback_wrapper)
aimrt_py_ros2.Ros2SubscribeWithCtx(subscriber, py_ros2_ts, msg_type, ros2_callback_wrapper)

else:
raise TypeError(f"Invalid message type: {type(msg_type)}, expected Protobuf or ROS2 message type")
Loading
Loading