Robotics StackExchange | Archived questions

Unable to Properly Kill Nodes Launched via Custom ROS Node

Hello ROS community,

I am facing an issue with a custom ROS node I have developed that can launch other nodes using a string command. I can successfully publish a string containing the launch command to start a node, but I am having trouble killing the nodes once they are launched.

I have implemented a CommandExecutor node that handles the launching and killing of nodes. The executecommandcallback function reads the string message and extracts the name and command to execute. If the command is "kill," it calls the kill_node method. However, despite the message in the console saying that the node is "killed," the node appears to be still running.

I've shared the relevant part of the code below for reference:

import rclpy
from rclpy.node import Node
from std_msgs.msg import String
import subprocess
import threading
import signal

class CommandExecutor(Node):
    def __init__(self):
        super().__init__('command_executor')
        self.subscription = self.create_subscription(
            String,
            'launch_node',
            self.execute_command_callback,
            10
          )
    self.running_processes = {}  # Dictionary to store the running processes with custom names

def execute_command_callback(self, msg):
    name, command = msg.data.split(" ", 1)  # Split the received string into command and name
    self.get_logger().info(f"name: '{name}' command: '{command}'.")
    if command == "kill":
        self.kill_node(name)  # Call the kill_node method using 'self'
    else:
        # Execute the launch command in a separate thread
        threading.Thread(target=self.execute_command, args=(name, command)).start()

def execute_command(self, name, launch_command):
    try:
        process_handle = subprocess.Popen(launch_command, shell=True, text=True)
        self.running_processes[name] = process_handle
        process_handle.wait()  # Wait for the process to finish
        if name in self.running_processes:
            del self.running_processes[name]  # Remove from the dictionary when done

    except Exception as e:
        self.get_logger().error(f"Failed to execute command: {e}")
    else:
        self.get_logger().info(f"Command executed: {launch_command}")

def kill_node(self, name):
    if name in self.running_processes:
        try:
            process_handle = self.running_processes[name]
            process_handle.send_signal(signal.SIGINT)
            process_handle.wait(timeout=30)
        except subprocess.TimeoutExpired:
            process_handle.kill()
            process_handle.wait()
        self.get_logger().info(f"Node '{name}' killed.")
    else:
        self.get_logger().info(f"No active node with name '{name}' to kill.")

def main(args=None):
    rclpy.init(args=args)
    node = CommandExecutor()
    rclpy.spin(node)
    node.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()

I've already attempted using subprocess.sendsignal(signal.SIGINT) to send the SIGINT signal to the process and processhandle.kill() as an alternative, but the node does not seem to terminate properly.

I would greatly appreciate any insights or suggestions to help me resolve this issue. If you need more information or any additional code snippets, please let me know.

Thank you in advance for your time and assistance!

Best regards, [Emil Harlan] [ROS 2 Foxy]

Asked by harrrlan on 2023-07-24 04:45:54 UTC

Comments

as a point of clarification - are you running nodes (ros2 run ...) or are you launching launch files (ros2 launch ...)? Its not very clear from your description.

I'd also suggest looking at the PID of the created process handle and comparing to the PIDs of running ROS processes (e.g. ps aux | grep ros). Does sigint kill the PID associated with the handle but there are other processes still running?

Or does sigint do nothing? In that case, can you kill the PID from the terminal? (kill PID)? If so, could you kill it using a subprocess call? (subprocess.run(f'kill {process_handle.pid}', shell=False))

In my experience, ROS processes started with subprocess using shell=True are a bit notorious for "hanging around" in the background and ignoring sigints or keyboard interrupts.

Asked by shonigmann on 2023-07-25 18:32:19 UTC

Answers