Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
22 commits
Select commit Hold shift + click to select a range
99a4488
Add century_ros package
pazeshun Jun 23, 2025
45afa78
[century_ros] Increase power_cycle_interval to ensure reset
pazeshun Jun 25, 2025
105ab09
[century_ros] Stop restarting usb_auto_power_cycle to prevent deadlock
pazeshun Jun 25, 2025
dda5a51
[century_ros] Ensure that USB is power on when driver is initialized
pazeshun Jun 25, 2025
0340e60
[century_ros] Print message when usb_auto_power_cycle stands by
pazeshun Jun 25, 2025
d948cb1
[century_ros] Increase default monitored_topic_allowed_delay_cycles t…
pazeshun Jun 25, 2025
2bec427
[century_ros] Add minimal usage to README
pazeshun Jun 25, 2025
d4e0ee9
[century_ros] Add more knowledge about how to connect USB-Serial trou…
pazeshun Jun 26, 2025
cf2120e
[century_ros] Improve compatibility of usb_auto_power_cycle with new …
pazeshun Jun 27, 2025
b1c01d1
[century_ros] Execute power cycle of USB once at the beginning of usb…
pazeshun Jun 27, 2025
70372f0
[century_ros] Enable to power off USB when driver is initialized
pazeshun Jul 4, 2025
0f386ba
century_ros -> power_switching_tools_ros
pazeshun Aug 6, 2025
3fde123
[power_switching_tools_ros] Make it easier to support new device
pazeshun Aug 6, 2025
30afe34
[power_switching_tools_ros] Support USB PPPS hubs
pazeshun Aug 6, 2025
29ec7ba
[power_switching_tools_ros] Enable to prepare multiple udev rules for…
pazeshun Aug 7, 2025
9d201be
[power_switching_tools_ros] Add another advantage of USB PPPS hubs
pazeshun Aug 7, 2025
23c1f1d
[power_switching_tools_ros] Enable to add supplementary options to uh…
pazeshun Aug 12, 2025
e312675
[power_switching_tools_ros] Add more document of power switching test
pazeshun Aug 12, 2025
363deb3
[power_switching_tools_ros] Fix udev setting script
pazeshun Aug 12, 2025
855d58d
[power_switching_tools_ros] Enable to set multiple hub_location and h…
pazeshun Aug 13, 2025
e8ef3a5
[power_switching_tools_ros] Add how to try latest uhubctl
pazeshun Sep 17, 2025
0e13655
[power_switching_tools_ros] Add webcam problem to README
pazeshun Oct 17, 2025
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
25 changes: 25 additions & 0 deletions power_switching_tools_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
cmake_minimum_required(VERSION 2.8.3)
project(power_switching_tools_ros)

find_package(catkin REQUIRED)

catkin_python_setup()

catkin_package()

file(GLOB NODE_SCRIPTS_PY node_scripts/*.py)
catkin_install_python(PROGRAMS ${NODE_SCRIPTS_PY}
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/node_scripts
)

install(DIRECTORY scripts
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
USE_SOURCE_PERMISSIONS
PATTERN "*"
PATTERN "*/*.py" EXCLUDE
)

install(DIRECTORY launch udev
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
USE_SOURCE_PERMISSIONS
)
192 changes: 192 additions & 0 deletions power_switching_tools_ros/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,192 @@
# power_switching_tools_ros

ROS tools for power switching tools.
Supported tools are:
- [USB-Serial troubleshooter](#usb-serial-troubleshooter)
- [USB PPPS hubs](#usb-ppps-hubs)

## [USB-Serial troubleshooter](https://www.century.co.jp/products/ct-3usb1hub.html)

### Preparation

#### Udev setting

This is optional, but we recommend this setting because USB-Serial troubleshooter is sometimes suddenly disconnected and its device file changes.
```bash
rosrun power_switching_tools_ros setup_udev_for_usb_serial_troubleshooter <serial_number> <symlink_name>
# <serial_number> : The serial number of your USB-Serial troubleshooter (e.g., 001A02F2046C). You can check the serial number by "udevadm info --name=/dev/ttyACM* --attribute-walk"
# <symlink_name> : The name to create as a symbolic link in /dev (e.g., usb_serial_troubleshooter1)
```

#### Connecting USB-Serial troubleshooter

When inserting your USB-Serial troubleshooter to your PC, check if LED in the troubleshooter becomes blue after a few moments.
If it remains red, the connection between the troubleshooter and the PC fails to be established.
If you face this phenomenon, try the following:
- Reversing USB-C connector of USB hub/adapter/cable if you connect the troubleshooter to a USB hub/adapter/cable connected to a USB-C port of the PC
- Connecting the troubleshooter to a USB-A port of the PC directly (not via a USB hub)
- Connecting the troubleshooter to a USB-C port of the PC via an adapter/cable ([example](https://www.amazon.co.jp/dp/B09SFS9C5K))
- Changing USB hub/adapter/cable
- Changing the insertion process. Our experience has shown that success is more likely to be achieved if the insertion is stopped at a shallow point and then immediately deepened
- Using USB 2.0 hub/adapter/cable. Note that you will be unable to use USB 3.0 features on the devices under the troubleshooter

### Minimal usage: launching driver only

```bash
roslaunch power_switching_tools_ros usb_serial_troubleshooter.launch port:=/dev/<symlink_name>
# <symlink_name> : The same as above
```

#### Arguments

Check them by `roslaunch power_switching_tools_ros usb_serial_troubleshooter.launch --ros-args`:
```
Required Arguments:
port: Port connecting with USB-Serial troubleshooter (e.g., '/dev/ttyACM0')
Optional Arguments:
init_with_power_on (default "true"): Power on USB when driver of USB-Serial troubleshooter is initialized. This argument is valid only when init_with_power_set is true
init_with_power_set (default "true"): Set power state of USB when driver of USB-Serial troubleshooter is initialized. Which state (ON or OFF) is set is defined by init_with_power_on
power_cycle_interval (default "1.0"): Interval [sec] in USB power cycle using USB-Serial troubleshooter
power_cycle_service (default "~power_cycle"): Name of service for USB power cycle
power_service (default "~power"): Name of service for USB power switching
serial_timeout (default "1"): Timeout [sec] of serial communication with USB-Serial troubleshooter
```

#### Services

- `usb_serial_troubleshooter_driver/power` (`std_srvs/SetBool`)

Power on/off USB.

- `usb_serial_troubleshooter_driver/power_cycle` (`std_srvs/Trigger`)

Execute power cycle of USB.

### Advanced usage: automated power cycle of USB

```bash
roslaunch power_switching_tools_ros auto_power_cycle.launch troubleshooter_port:=/dev/<symlink_name> monitored_topic:=<monitored_topic> monitored_topic_expected_hz:=<monitored_topic_expected_hz> monitored_topic_respawn_delay:=<monitored_topic_respawn_delay>
# <symlink_name> : The same as above
# <monitored_topic> : Topic monitored for determining health of monitored communication. If this is not published for an unusually long period, power cycle of that communication occurs
# <monitored_topic_expected_hz> : Expected Hz of monitored topic
# <monitored_topic_respawn_delay> : For this duration [sec] after power cycle, new power cycle does not occur to wait for topic to be published
#
# In default, this launch firstly executes power cycle once. If you want to change this behavior, set "init_with_power_cycle:=false"
```

## USB PPPS hubs

"PPPS" stands for "Per-Port Power Switching" which is an advanced functionality of USB hubs.
Hubs supporting PPPS (e.g., [VirtualHere USB 3 4-Port Hub](https://modularkvmip.com/product/usb-hub/)) are listed [here](https://github.com/mvp/uhubctl?tab=readme-ov-file#compatible-usb-hubs).
- Advantages compared with USB-Serial troubleshooter:
- Having multiple ports
- [Connection problem](#connecting-usb-serial-troubleshooter) does not occur
- Disadvantages compared with USB-Serial troubleshooter:
- Power switching is slower
- Some devices show unexpected behavior after you command your hub to power off them
- [Power comes back on after few seconds](https://github.com/mvp/uhubctl?tab=readme-ov-file#power-comes-back-on-after-few-seconds-on-linux)
- Power comes back on when the device is accessed.
This behavior was observed when webcams were used on Ubuntu 20.04 (not observed on Ubuntu 24.04).
This behavior is slightly different from the first behavior because the first behavior depends on no external access.
The workarounds for the first behavior on Ubuntu 20.04 (i.e., Linux 5.x) mentioned in the document do not work for the second behavior

### Preparation

#### Udev setting

This is required for running the driver node without `sudo`.
```bash
rosrun power_switching_tools_ros setup_udev_for_usb_ppps_hub
# Reboot your PC after this script finishes
# Note that this script adds your user to dialout group, which means "chmod" becomes unnecessary for accessing some device files (e.g., /dev/ttyACM0)
```

#### Check if power switching works

Connect your hub to your PC, connect devices you want to use in your application to your hub, then run:
```bash
uhubctl # If this command is not found, install it by "sudo apt install uhubctl"
```
You will get an output like:
```
Current status for hub 3-5 [366b:0004 VirtualHere Pty. Ltd. VirtualHere 4-Port Hub 91B35D672F3E3755, USB 2.10, 4 ports]
Port 1: 0103 power enable connect [2341:0058 Arduino LLC Arduino Nano Every 059D618F51514C4B38202020FF171A11]
Port 2: 0100 power
Port 3: 0100 power
Port 4: 0100 power
Current status for hub 2-2 [366b:0005 VirtualHere Pty. Ltd. VirtualHere 4-Port Hub 91B35D672F3E3755, USB 3.20, 4 ports]
Port 1: 06a0 power Rx.Detect
Port 2: 06a0 power Rx.Detect
Port 3: 06a0 power Rx.Detect
Port 4: 06a0 power Rx.Detect
```
Write down the number just after `Current status for hub` whose section includes the device you want to power on/off (`3-5`, in the example above).
This is the location of your hub.
In addition, write down the port which that device is connected to (`1`, in the example above).
Then try to power off and on the device:
```bash
uhubctl -a off -l <hub_location> -p <hub_port>
# <hub_location> : Location of your hub
# <hub_port> : Port of your hub which you want to power on/off
uhubctl -a on -l <hub_location> -p <hub_port>
```
If USB power supply to the device is stopped and restarted as expected, `power_switching_tools_ros` can also power on/off the device.
If not, try the latest version of `uhubctl`:
```bash
cd ~
git clone https://github.com/mvp/uhubctl.git
cd uhubctl
make
./uhubctl -a off -l <hub_location> -p <hub_port>
./uhubctl -a on -l <hub_location> -p <hub_port>
```
If this works as expected, use `~/uhubctl/uhubctl` to control your hub in the following (i.e., pass `uhubctl_executable:=~/uhubctl/uhubctl` to `usb_ppps_hub.launch`).
If not, check [the web page of uhubctl](https://github.com/mvp/uhubctl) (especially [FAQ](https://github.com/mvp/uhubctl?tab=readme-ov-file#faq)) to find candidates for a workaround and try them.
If the found workaround requires supplementary options for `uhubctl`, write them down.

### Minimal usage: launching driver only

```bash
roslaunch power_switching_tools_ros usb_ppps_hub.launch hub_location:=<hub_location> hub_port:=<hub_port>
# <hub_location> : Location of your hub
# <hub_port> : Port of your hub which you want to power on/off
```
If [the previous checking](#check-if-power-switching-works) tells you to use the latest `uhubctl` and/or add supplementary options to `uhubctl`, use `uhubctl_executable` argument explained below.

#### Arguments

Check them by `roslaunch power_switching_tools_ros usb_ppps_hub.launch --ros-args`:
```
Required Arguments:
hub_location: Location(s) of USB PPPS hub (e.g., '3-5', '[3-5, 2-2]', , '[3-5, 3-5]')
hub_port: Port(s) of USB PPPS hub you want to power on/off (e.g., '1', '[1, 1]', '[1, 2]'). Must be the same length as hub_location and each element corresponds to the element at the same position in hub_location
Optional Arguments:
init_with_power_on (default "true"): Power on USB when driver of USB PPPS hub is initialized. This argument is valid only when init_with_power_set is true
init_with_power_set (default "true"): Set power state of USB when driver of USB PPPS hub is initialized. Which state (ON or OFF) is set is defined by init_with_power_on
power_cycle_interval (default "1.0"): Interval [sec] in USB power cycle using USB PPPS hub
power_cycle_service (default "~power_cycle"): Name of service for USB power cycle
power_service (default "~power"): Name of service for USB power switching
uhubctl_executable (default "uhubctl"): Command to control USB PPPS hub. You can add supplementary options to uhubctl command (e.g., 'uhubctl -r 100'). In addition, you can specify the path to uhubctl command you installed on your own (e.g., '~/uhubctl/uhubctl')
```

#### Services

- `usb_ppps_hub_driver/power` (`std_srvs/SetBool`)

Power on/off the target port.

- `usb_ppps_hub_driver/power_cycle` (`std_srvs/Trigger`)

Execute power cycle of the target port.

### Advanced usage: automated power cycle of USB hub port

```bash
roslaunch power_switching_tools_ros usb_ppps_hub.launch power_cycle_service:=auto_power_cycle/power_cycle hub_location:=<hub_location> hub_port:=<hub_port>
roslaunch power_switching_tools_ros auto_power_cycle.launch launch_default_driver:=false monitored_topic:=<monitored_topic> monitored_topic_expected_hz:=<monitored_topic_expected_hz> monitored_topic_respawn_delay:=<monitored_topic_respawn_delay>
# <monitored_topic> : Topic monitored for determining health of monitored communication. If this is not published for an unusually long period, power cycle of that communication occurs
# <monitored_topic_expected_hz> : Expected Hz of monitored topic
# <monitored_topic_respawn_delay> : For this duration [sec] after power cycle, new power cycle does not occur to wait for topic to be published
#
# In default, this launch firstly executes power cycle once. If you want to change this behavior, set "init_with_power_cycle:=false"
```
53 changes: 53 additions & 0 deletions power_switching_tools_ros/launch/auto_power_cycle.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
<launch>

<arg name="monitored_topic"
doc="Topic monitored for determining health of monitored communication. If this is not published for an unusually long period, power cycle of that communication occurs" />
<arg name="monitored_topic_expected_hz"
doc="Expected Hz of monitored topic" />
<arg name="monitored_topic_respawn_delay"
doc="For this duration [sec] after power cycle, new power cycle does not occur to wait for topic to be published" />

<arg name="launch_default_driver" default="true"
doc="Launch driver of USB-Serial troubleshooter" />
<arg name="troubleshooter_port" default="/dev/ttyACM0"
doc="Port connecting with USB-Serial troubleshooter" />
<arg name="troubleshooter_serial_timeout" default="1"
doc="Timeout [sec] of serial communication with USB-Serial troubleshooter" />
<arg name="troubleshooter_power_cycle_interval" default="1.0"
doc="Interval [sec] in USB power cycle using USB-Serial troubleshooter" />
<arg name="troubleshooter_init_with_power_set" default="true"
doc="Set power state of USB when driver of USB-Serial troubleshooter is initialized. Which state (ON or OFF) is set is defined by troubleshooter_init_with_power_on" />
<arg name="troubleshooter_init_with_power_on" default="true"
doc="Power on USB when driver of USB-Serial troubleshooter is initialized. This argument is valid only when troubleshooter_init_with_power_set is true" />
<arg name="monitored_topic_allowed_delay_cycles" default="2.0"
doc="If monitored topic is not published in the expected timing and is delayed for ((1 / monitored_topic_expected_hz) * monitored_topic_allowed_delay_cycles) [sec], power cycle occurs" />
<arg name="init_with_power_cycle" default="true"
doc="Execute power cycle when auto_power_cycle node is initialized" />

<group if="$(arg launch_default_driver)">

<include file="$(find power_switching_tools_ros)/launch/usb_serial_troubleshooter.launch">
<arg name="port" value="$(arg troubleshooter_port)" />
<arg name="serial_timeout" value="$(arg troubleshooter_serial_timeout)" />
<arg name="power_cycle_interval" value="$(arg troubleshooter_power_cycle_interval)" />
<arg name="init_with_power_set" value="$(arg troubleshooter_init_with_power_set)" />
<arg name="init_with_power_on" value="$(arg troubleshooter_init_with_power_on)" />
<arg name="power_cycle_service" value="auto_power_cycle/power_cycle" />
</include>

</group>

<node name="auto_power_cycle"
pkg="power_switching_tools_ros" type="auto_power_cycle.py"
respawn="true"
output="screen">
<remap from="~monitored_topic" to="$(arg monitored_topic)" />
<rosparam subst_value="true">
monitored_topic_expected_hz: $(arg monitored_topic_expected_hz)
monitored_topic_allowed_delay_cycles: $(arg monitored_topic_allowed_delay_cycles)
monitored_topic_respawn_delay: $(arg monitored_topic_respawn_delay)
init_with_power_cycle: $(arg init_with_power_cycle)
</rosparam>
</node>

</launch>
37 changes: 37 additions & 0 deletions power_switching_tools_ros/launch/usb_ppps_hub.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
<launch>

<arg name="hub_location"
doc="Location(s) of USB PPPS hub (e.g., '3-5', '[3-5, 2-2]', , '[3-5, 3-5]')" />
<arg name="hub_port"
doc="Port(s) of USB PPPS hub you want to power on/off (e.g., '1', '[1, 1]', '[1, 2]'). Must be the same length as hub_location and each element corresponds to the element at the same position in hub_location" />

<arg name="power_cycle_interval" default="1.0"
doc="Interval [sec] in USB power cycle using USB PPPS hub" />
<arg name="init_with_power_set" default="true"
doc="Set power state of USB when driver of USB PPPS hub is initialized. Which state (ON or OFF) is set is defined by init_with_power_on" />
<arg name="init_with_power_on" default="true"
doc="Power on USB when driver of USB PPPS hub is initialized. This argument is valid only when init_with_power_set is true" />
<arg name="power_service" default="~power"
doc="Name of service for USB power switching" />
<arg name="power_cycle_service" default="~power_cycle"
doc="Name of service for USB power cycle" />
<arg name="uhubctl_executable" default="uhubctl"
doc="Command to control USB PPPS hub. You can add supplementary options to uhubctl command (e.g., 'uhubctl -r 100'). In addition, you can specify the path to uhubctl command you installed on your own (e.g., '~/uhubctl/uhubctl')" />

<node name="usb_ppps_hub_driver"
pkg="power_switching_tools_ros" type="usb_ppps_hub_driver.py"
respawn="true"
output="screen">
<remap from="~power" to="$(arg power_service)" />
<remap from="~power_cycle" to="$(arg power_cycle_service)" />
<rosparam subst_value="true">
hub_location: $(arg hub_location)
hub_port: $(arg hub_port)
power_cycle_interval: $(arg power_cycle_interval)
init_with_power_set: $(arg init_with_power_set)
init_with_power_on: $(arg init_with_power_on)
uhubctl_executable: $(arg uhubctl_executable)
</rosparam>
</node>

</launch>
34 changes: 34 additions & 0 deletions power_switching_tools_ros/launch/usb_serial_troubleshooter.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
<launch>

<arg name="port"
doc="Port connecting with USB-Serial troubleshooter (e.g., '/dev/ttyACM0')" />

<arg name="serial_timeout" default="1"
doc="Timeout [sec] of serial communication with USB-Serial troubleshooter" />
<arg name="power_cycle_interval" default="1.0"
doc="Interval [sec] in USB power cycle using USB-Serial troubleshooter" />
<arg name="init_with_power_set" default="true"
doc="Set power state of USB when driver of USB-Serial troubleshooter is initialized. Which state (ON or OFF) is set is defined by init_with_power_on" />
<arg name="init_with_power_on" default="true"
doc="Power on USB when driver of USB-Serial troubleshooter is initialized. This argument is valid only when init_with_power_set is true" />
<arg name="power_service" default="~power"
doc="Name of service for USB power switching" />
<arg name="power_cycle_service" default="~power_cycle"
doc="Name of service for USB power cycle" />

<node name="usb_serial_troubleshooter_driver"
pkg="power_switching_tools_ros" type="usb_serial_troubleshooter_driver.py"
respawn="true"
output="screen">
<remap from="~power" to="$(arg power_service)" />
<remap from="~power_cycle" to="$(arg power_cycle_service)" />
<rosparam subst_value="true">
port: $(arg port)
serial_timeout: $(arg serial_timeout)
power_cycle_interval: $(arg power_cycle_interval)
init_with_power_set: $(arg init_with_power_set)
init_with_power_on: $(arg init_with_power_on)
</rosparam>
</node>

</launch>
Loading
Loading