Skip to content

Commit

Permalink
WIP: Support for ros launch with a new rule
Browse files Browse the repository at this point in the history
  • Loading branch information
adityapande-1995 authored and EricCousineau-TRI committed Mar 9, 2024
1 parent 4c17af0 commit 1ddf90e
Show file tree
Hide file tree
Showing 10 changed files with 220 additions and 0 deletions.
11 changes: 11 additions & 0 deletions bazel_ros2_rules/ros2/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,17 @@ py_library(
deps = ["@bazel_tools//tools/python/runfiles"],
)

py_library(
name = "roslaunch_util.py",
srcs = [
"tools/roslaunch_util/__init__.py",
"tools/roslaunch_util/roslaunch_util.py",
"tools/roslaunch_util/setup.py",
],
visibility = ["//visibility:public"],
deps = ["@bazel_tools//tools/python/runfiles"],
)

run_calculate_rosidl_capitalization_tests()

py_library(
Expand Down
20 changes: 20 additions & 0 deletions bazel_ros2_rules/ros2/ros_py.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,26 @@ def ros_py_binary(
)
py_binary_rule(name = name, **kwargs)

def ros_launch(
name,
launch_file = None,
node_targets = []):
deps = ["@ros2//:ros2", "@bazel_ros2_rules//ros2:roslaunch_util.py"]
srcs = ["@bazel_ros2_rules//ros2:roslaunch_util.py"]

data = [launch_file]
data += node_targets
args = [launch_file]

ros_py_binary(
name = name,
main = "@bazel_ros2_rules//ros2:roslaunch_util.py",
deps = deps,
srcs = srcs,
data = data,
args = args,
)

def ros_py_test(
name,
rmw_implementation = None,
Expand Down
3 changes: 3 additions & 0 deletions bazel_ros2_rules/ros2/tools/roslaunch_util/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
from .roslaunch_util import ExecuteBazelTarget

__all__ = ['ExecuteBazelTarget']
52 changes: 52 additions & 0 deletions bazel_ros2_rules/ros2/tools/roslaunch_util/roslaunch_util.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
import subprocess
import sys
import os

from launch.actions import ExecuteProcess
from launch.frontend import expose_action

# This util file serves as a wrapper over the cmdline
# way to run launch, using "ros2 launch launch_file.py".
# The ros_launch() bazel rule starts this script, which
# gets run as a ros_py_binary(). This way we get the ros
# environment set up for us for free.

def find_rel_path(name, path):
for root, _, files in os.walk(path):
if name in files:
return os.path.relpath(os.path.join(root, name))

# Launch action to wrap over ExecuteProcess.
@expose_action('execute_bazel_target')
class ExecuteBazelTarget(ExecuteProcess):
def __init__(self,target,**kwargs):
super().__init__(cmd=[find_rel_path(target, os.getcwd())],
**kwargs)

@classmethod
def parse(cls, entity, parser):
_, kwargs = super().parse(entity, parser, ignore=['cmd'])
kwargs['target'] = entity.get_attr('target')
return cls, kwargs

def execute(self, context):
return super().execute(context)

if __name__ == '__main__':
# TODO (Aditya): How do I stop installing this every time ?
# Required to get xml launch working, as we need to register an entry
# point for launch extensions.
os.system("pip install ../bazel_ros2_rules/ros2/tools/roslaunch_util >/dev/null 2>&1")
# Actual launch files should be able to import the custom action now.
env = {**os.environ, 'PYTHONPATH': os.getcwd() + '/external/bazel_ros2_rules/ros2/tools:'
+ os.environ['PYTHONPATH']}

launch_file_name = sys.argv[1]

roslaunch_cli = "./external/ros2/ros2"
action = "launch"
# TODO : Is there a better way to locate the launch file exactly ?
launch_file = find_rel_path(launch_file_name, os.getcwd())

# This basically runs "ros2 launch launch_file"
subprocess.run([roslaunch_cli, action, launch_file], env=env)
10 changes: 10 additions & 0 deletions bazel_ros2_rules/ros2/tools/roslaunch_util/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
from setuptools import setup

setup(
name = "roslaunch_util",
entry_points={
'launch.frontend.launch_extension': [
'roslaunch_util = roslaunch_util',
],
}
)
40 changes: 40 additions & 0 deletions ros2_example_bazel_installed/ros2_example_apps/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
load("@ros2//:ros_cc.bzl", "ros_cc_binary")
load("@ros2//:ros_cc.bzl", "ros_cc_test")
load("@ros2//:ros_py.bzl", "ros_py_binary", "ros_py_test")
load("@ros2//:ros_py.bzl", "ros_launch")
load("@ros2//:rosidl.bzl", "rosidl_interfaces_group")
load("//tools:cmd_test.bzl", "cmd_test")

Expand Down Expand Up @@ -202,6 +203,45 @@ ros_py_binary(
],
)

# ROS launch example.
ros_py_binary(
name = "eg_talker",
srcs = ["roslaunch_eg_nodes/eg_talker.py"],
deps = [
"@ros2//:rclpy_py",
"@ros2//:std_msgs_py",
],
)

ros_cc_binary(
name = "eg_listener",
srcs = ["roslaunch_eg_nodes/eg_listener.cpp"],
deps = [
"@ros2//:rclcpp_cc",
"@ros2//:std_msgs_cc",
],
)

# Uses a python launch file to spawn the talker and listener.
ros_launch(
name = "roslaunch_eg_py",
launch_file = "eg_launch.py",
node_targets = [
":eg_talker",
":eg_listener",
],
)

# Uses an xml launch file to spawn the talker and listener.
ros_launch(
name = "roslaunch_eg_xml",
launch_file = "eg_launch.xml",
node_targets = [
":eg_talker",
":eg_listener",
],
)

ros_py_test(
name = "custom_message_rosbag_test",
srcs = ["test/custom_message_rosbag_test.py"],
Expand Down
10 changes: 10 additions & 0 deletions ros2_example_bazel_installed/ros2_example_apps/eg_launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
from launch import LaunchDescription
from roslaunch_util import ExecuteBazelTarget

def generate_launch_description():
return LaunchDescription([
# Running a talker written in python.
ExecuteBazelTarget('eg_talker'),
# Running a listener written in cpp.
ExecuteBazelTarget('eg_listener'),
])
4 changes: 4 additions & 0 deletions ros2_example_bazel_installed/ros2_example_apps/eg_launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
<launch>
<execute_bazel_target target="eg_talker"/>
<execute_bazel_target target="eg_listener"/>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
using std::placeholders::_1;

class MinimalSubscriber : public rclcpp::Node
{
public:
MinimalSubscriber()
: Node("minimal_subscriber")
{
subscription_ = this->create_subscription<std_msgs::msg::String>(
"topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1));
}

private:
void topic_callback(const std_msgs::msg::String::SharedPtr msg) const
{
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
}
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
};

int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalSubscriber>());
rclcpp::shutdown();
return 0;
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
import rclpy
from rclpy.node import Node

from std_msgs.msg import String


class MinimalPublisher(Node):

def __init__(self):
super().__init__('minimal_publisher')
self.publisher_ = self.create_publisher(String, 'topic', 10)
timer_period = 0.5 # seconds
self.timer = self.create_timer(timer_period, self.timer_callback)
self.i = 0

def timer_callback(self):
msg = String()
msg.data = 'Hello World: %d' % self.i
self.publisher_.publish(msg)
self.get_logger().info('Publishing: "%s"' % msg.data)
self.i += 1


def main(args=None):
rclpy.init(args=args)

minimal_publisher = MinimalPublisher()

rclpy.spin(minimal_publisher)

# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
minimal_publisher.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
main()

0 comments on commit 1ddf90e

Please sign in to comment.