Skip to content

Commit

Permalink
(fix) Removes setproctitle as a hard dependency
Browse files Browse the repository at this point in the history
  • Loading branch information
aleph-ra committed Feb 10, 2025
1 parent 3d8f165 commit 0d7c4ca
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 7 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ A [Component](https://automatika-robotics.github.io/ros-sugar/design/component.h

Install python dependencies using pip as follows:

`pip install 'attrs>=23.2.0' msgpack-numpy numpy-quaternion setproctitle`
`pip install 'attrs>=23.2.0' msgpack-numpy`

Grab your favorite deb package from the [release page](https://github.com/automatika-robotics/ros-sugar/releases) and install it as follows:

Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
<depend>python3-opencv</depend>
<depend>python3-jinja2</depend>
<depend>python3-msgpack</depend>
<depend>python-numpy-quaternion-pip</depend>

<test_depend>ament_cmake_pytest</test_depend>
<test_depend>ament_index_python</test_depend>
Expand Down
10 changes: 7 additions & 3 deletions ros_sugar/launch/executable.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
from typing import Optional, List, Type, Tuple

import rclpy
import setproctitle
from rclpy.executors import MultiThreadedExecutor
from rclpy.utilities import try_shutdown

Expand Down Expand Up @@ -189,8 +188,13 @@ def main(args=None):
if not component_name:
raise ValueError("Cannot launch component without specifying a name")

# SET PROCESS NAME
setproctitle.setproctitle(component_name)
# TODO: add setproctitle as install dependancy when available in rosdep
# SET PROCESS NAME (if setproctitle is available)
try:
import setproctitle
setproctitle.setproctitle(component_name)
except ImportError:
pass

config = _parse_component_config(args, list_of_configs)

Expand Down
10 changes: 7 additions & 3 deletions ros_sugar/launch/launcher.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
import msgpack_numpy as m_pack
import launch
import rclpy
import setproctitle
from launch import LaunchDescription, LaunchIntrospector, LaunchService
from launch.action import Action as ROSLaunchAction
from launch.actions import (
Expand Down Expand Up @@ -802,8 +801,13 @@ def setup_launch_description(
):
self._check_duplicate_names()

# SET PROCESS NAME
setproctitle.setproctitle(logger.name)
# TODO: add setproctitle as install dependancy when available in rosdep
# SET PROCESS NAME (if setproctitle is available)
try:
import setproctitle
setproctitle.setproctitle(logger.name)
except ImportError:
pass

self._setup_monitor_node()

Expand Down

0 comments on commit 0d7c4ca

Please sign in to comment.