Skip to content

Commit

Permalink
[roswtf plugin] Replace with Linux-dependent command.
Browse files Browse the repository at this point in the history
  • Loading branch information
130s committed Jun 7, 2018
1 parent 7c6bd1a commit 3de8ff9
Show file tree
Hide file tree
Showing 2 changed files with 36 additions and 3 deletions.
1 change: 0 additions & 1 deletion openni2_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
<run_depend>image_proc</run_depend>
<run_depend>nodelet</run_depend>
<run_depend>openni2_camera</run_depend>
<run_depend>python-usb</run_depend>
<run_depend>rospy</run_depend>
<run_depend>roswtf</run_depend>
<run_depend>tf</run_depend>
Expand Down
38 changes: 36 additions & 2 deletions openni2_launch/src/openni2_launch/wtf_plugin.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,45 @@
# POSSIBILITY OF SUCH DAMAGE.

from __future__ import print_function
import logging
import re
import subprocess

import rospy
from roswtf.rules import warning_rule, error_rule


def _device_notfound_subproc(id_manufacturer, id_product):
"""
@rtype: [dict]
@return: Example:
[{'device': '/dev/bus/usb/002/004', 'tag': 'Lenovo ', 'id': '17ef:305a'},
{'device': '/dev/bus/usb/002/001', 'tag': 'Linux Foundation 3.0 root hub', 'id': '1d6b:0003'},
{'device': '/dev/bus/usb/001/006', 'tag': 'Validity Sensors, Inc. ', 'id': '138a:0090'},,,]
@note: This method depends on Linux command (via subprocess), which makes
this command platform-dependent. Ubuntu Xenial onward, a Python module
that encapsulate platform operation becomes available so this method
can be wiped out. See https://github.com/ros-drivers/openni2_camera/pull/80#discussion_r193295442
"""
device_re = re.compile("Bus\s+(?P<bus>\d+)\s+Device\s+(?P<device>\d+).+ID\s(?P<id>\w+:\w+)\s(?P<tag>.+)$", re.I)
df = subprocess.check_output("lsusb")
devices = []
for i in df.split('\n'):
if i:
info = device_re.match(i)
if info:
dinfo = info.groupdict()
print("dinfo: {}, dinfo.id: {}".format(dinfo, dinfo["id"]))
logging.debug("dinfo: {}, dinfo.id: {}".format(dinfo, dinfo["id"]))
if dinfo["id"] == "{}:{}".format(id_manufacturer, id_product):
dinfo['device'] = "/dev/bus/usb/{}/{}".format(dinfo.pop('bus'), dinfo.pop('device'))
devices.append(dinfo)
logging.info("#devices: {}\ndevices: {}".format(len(devices), devices))
return devices


def sensor_notfound(ctx):
"""
@summary: Check if expected number of sensors are found.
Expand All @@ -45,10 +77,12 @@ def sensor_notfound(ctx):
"""
errors = []
num_sensors_expected = rospy.get_param("openni2_num_sensors", 1)

# TODO: The set of manufacture id and prod id is specific to Asus Xtion.
# There may be other openni2-based devices.
devices = usb.core.find(idVendor=0x1d27, idProduct=0x0601, find_all=True)
num_sensors = sum(1 for _ in devices)
devices = _device_notfound_subproc(
id_manufacturer="1d27", id_product="0601")
num_sensors = len(devices)
if num_sensors != num_sensors_expected:
errors.append("{} openni2 sensors found (expected: {}).".format(
num_sensors, num_sensors_expected))
Expand Down

0 comments on commit 3de8ff9

Please sign in to comment.