diff --git a/robomaster_pi/launch_node.py b/robomaster_pi/launch_node.py new file mode 100644 index 0000000000000000000000000000000000000000..6f28c03f1492b758ded1ecdd179fd8199db6d2a0 --- /dev/null +++ b/robomaster_pi/launch_node.py @@ -0,0 +1,49 @@ +import rclpy +from rclpy.node import Node +from rclpy.subscription import Subscription +from std_msgs.msg import String +from subprocess import Popen +from concurrent.futures import ThreadPoolExecutor + +class LaunchNode(Node): + + def __init__(self): + super().__init__("launch_node") + + # Subscribe to the launch_node topic + self.subscription = self.create_subscription( + String, "launch_node", self.on_message, 10) + + # Create a dictionary to store the launched processes + self.launched_processes = {} + + # Create a thread pool + self.thread_pool = ThreadPoolExecutor(max_workers=10) + + def on_message(self, msg): + # Get the launch command and name from the message + name = msg.name + command = msg.command + + # If the launch command is "kill", send a SIGINT signal to the process with the given name + if command == "kill": + if name in self.launched_processes: + os.kill(self.launched_processes[name], signal.SIGINT) + del self.launched_processes[name] + else: + # Otherwise, launch the process with the given command + self.thread_pool.submit(self.launch_process, name, command) + + def launch_process(self, name, command): + # Launch the process + process = Popen(command) + self.launched_processes[name] = process + +def main(): + rclpy.init() + node = LaunchNode() + rclpy.spin(node) + rclpy.shutdown() + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/setup.py b/setup.py index b96eb0a772376577fb310f8e9cd999cc6560c5f3..889e6a290c830631c2651c6177dd81e3eaec681d 100644 --- a/setup.py +++ b/setup.py @@ -20,6 +20,7 @@ setup( tests_require=['pytest'], entry_points={ 'console_scripts': [ + "launch_node =robomaster_pi.launch_node:main" "cmd_vel_combiner = robomaster_pi.cmd_vel_combiner:main", "map_update = robomaster_pi.map_update:main", "command_executer = robomaster_pi.command_executer:main",