From 3a63e826c0d75b538e22339d8bb2ce253ac350f7 Mon Sep 17 00:00:00 2001 From: Jules Berhault <57791382+julesberhault@users.noreply.github.com> Date: Tue, 27 Sep 2022 10:44:40 +0200 Subject: [PATCH 01/46] Adding CMAKE_EXE_LINKER_FLAGS in CMakeLists.txt Adding CMAKE_EXE_LINKER_FLAGS in CMakeLists.txt to fix missing library issue while executing rosping. --- rosping/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/rosping/CMakeLists.txt b/rosping/CMakeLists.txt index 33c3af3a1..cecf3ebad 100644 --- a/rosping/CMakeLists.txt +++ b/rosping/CMakeLists.txt @@ -2,6 +2,8 @@ cmake_minimum_required(VERSION 2.8.3) project(rosping) +SET(CMAKE_EXE_LINKER_FLAGS "-Wl,--disable-new-dtags") + find_package(catkin REQUIRED COMPONENTS roscpp std_msgs rostest) # Set the build type. Options are: From 5083557998f5721da2f1ead0fe1dc6e9449bd4c5 Mon Sep 17 00:00:00 2001 From: y-yosuke Date: Tue, 25 Jul 2023 18:13:59 +0900 Subject: [PATCH 02/46] mod with SwitchBot API v1.1 --- switchbot_ros/launch/switchbot.launch | 2 + switchbot_ros/scripts/control_switchbot.py | 15 +++++ switchbot_ros/scripts/switchbot_ros_server.py | 45 ++++++++++++-- switchbot_ros/src/switchbot_ros/switchbot.py | 60 ++++++++++++++----- 4 files changed, 102 insertions(+), 20 deletions(-) create mode 100644 switchbot_ros/scripts/control_switchbot.py diff --git a/switchbot_ros/launch/switchbot.launch b/switchbot_ros/launch/switchbot.launch index b2a4d2aba..f5644e047 100644 --- a/switchbot_ros/launch/switchbot.launch +++ b/switchbot_ros/launch/switchbot.launch @@ -1,11 +1,13 @@ + token: $(arg token) + secret: $(arg secret) diff --git a/switchbot_ros/scripts/control_switchbot.py b/switchbot_ros/scripts/control_switchbot.py new file mode 100644 index 000000000..1c04c2b73 --- /dev/null +++ b/switchbot_ros/scripts/control_switchbot.py @@ -0,0 +1,15 @@ +#!/usr/bin/env python + +import rospy +from switchbot_ros.switchbot_ros_client import SwitchBotROSClient + +rospy.init_node('controler_node') +client = SwitchBotROSClient() + +devices = client.get_devices() +print(devices) + +client.control_device('pendant-light', 'turnOff') + +client.control_device('bot74a', 'turnOn') + diff --git a/switchbot_ros/scripts/switchbot_ros_server.py b/switchbot_ros/scripts/switchbot_ros_server.py index 2793cb892..41b4b526f 100755 --- a/switchbot_ros/scripts/switchbot_ros_server.py +++ b/switchbot_ros/scripts/switchbot_ros_server.py @@ -26,6 +26,15 @@ def __init__(self): self.token = f.read().replace('\n', '') else: self.token = token + + # Switchbot API v1.1 needs secret key + secret = rospy.get_param('~secret') + if os.path.exists(secret): + with open(secret) as f: + self.secret = f.read().replace('\n', '') + else: + self.secret = secret + # Initialize switchbot client self.bots = self.get_switchbot_client() self.print_devices() @@ -40,7 +49,7 @@ def __init__(self): def get_switchbot_client(self): try: - client = SwitchBotAPIClient(token=self.token) + client = SwitchBotAPIClient(token=self.token, secret=self.secret) rospy.loginfo('Switchbot API Client initialized.') return client except ConnectionError: # If the machine is not connected to the internet @@ -60,20 +69,36 @@ def spin(self): def print_devices(self): if self.bots is None: return - device_list_str = 'Switchbot device list:\n' + + device_list_str = 'Switchbot Device List:\n' device_list = sorted( self.bots.device_list, key=lambda device: str(device['deviceName'])) for device in device_list: - device_list_str += 'Name: ' + str(device['deviceName']) - device_list_str += ', Type: ' + str(device['deviceType']) + device_list_str += 'deviceName: ' + str(device['deviceName']) + device_list_str += ', deviceID: ' + str(device['deviceId']) + device_list_str += ', deviceType: ' + str(device['deviceType']) device_list_str += '\n' rospy.loginfo(device_list_str) + + remote_list_str = 'Switchbot Remote List:\n' + infrared_remote_list = sorted( + self.bots.infrared_remote_list, + key=lambda infrared_remote: str(infrared_remote['deviceName'])) + for infrared_remote in infrared_remote_list: + remote_list_str += 'deviceName: ' + str(infrared_remote['deviceName']) + remote_list_str += ', deviceID: ' + str(infrared_remote['deviceId']) + remote_list_str += ', remoteType: ' + str(infrared_remote['remoteType']) + remote_list_str += '\n' + rospy.loginfo(remote_list_str) + def publish_devices(self): if self.bots is None: return + msg = DeviceArray() + device_list = sorted( self.bots.device_list, key=lambda device: str(device['deviceName'])) @@ -82,6 +107,16 @@ def publish_devices(self): msg_device.name = str(device['deviceName']) msg_device.type = str(device['deviceType']) msg.devices.append(msg_device) + + infrared_remote_list = sorted( + self.bots.infrared_remote_list, + key=lambda infrared_remote: str(infrared_remote['deviceName'])) + for infrared_remote in infrared_remote_list: + msg_device = Device() + msg_device.name = str(infrared_remote['deviceName']) + msg_device.type = str(infrared_remote['remoteType']) + msg.devices.append(msg_device) + self.pub.publish(msg) def execute_cb(self, goal): @@ -97,7 +132,7 @@ def execute_cb(self, goal): command_type = 'command' try: if not self.bots: - self.bots = SwitchBotAPIClient(token=self.token) + self.bots = SwitchBotAPIClient(token=self.token,secret=self.secret) feedback.status = str( self.bots.control_device( command=goal.command, diff --git a/switchbot_ros/src/switchbot_ros/switchbot.py b/switchbot_ros/src/switchbot_ros/switchbot.py index e7f75df21..7c5df04bf 100644 --- a/switchbot_ros/src/switchbot_ros/switchbot.py +++ b/switchbot_ros/src/switchbot_ros/switchbot.py @@ -4,15 +4,23 @@ import os.path import requests +import os +import time +import hashlib +import hmac +import base64 +import uuid + class SwitchBotAPIClient(object): """ For Using SwitchBot via official API. Please see https://github.com/OpenWonderLabs/SwitchBotAPI for details. """ - def __init__(self, token): - self._host_domain = "https://api.switch-bot.com/v1.0/" + def __init__(self, token, secret): + self._host_domain = "https://api.switch-bot.com/v1.1/" self.token = token + self.secret = secret # SwitchBot API v1.1 self.device_list = None self.infrared_remote_list = None self.scene_list = None @@ -21,6 +29,28 @@ def __init__(self, token): self.update_device_list() self.update_scene_list() + def make_sign(self, token: str, secret: str): + + nonce = uuid.uuid4() + t = int(round(time.time() * 1000)) + string_to_sign = '{}{}{}'.format(token, t, nonce) + + string_to_sign = bytes(string_to_sign, 'utf-8') + secret = bytes(secret, 'utf-8') + + sign = base64.b64encode(hmac.new(secret, msg=string_to_sign, digestmod=hashlib.sha256).digest()) + + return sign, str(t), nonce + + def make_request_header(self, token: str, secret: str): + sign,t,nonce = self.make_sign(token, secret) + headers={ + "Authorization": token, + "sign": str(sign, 'utf-8'), + "t": str(t), + "nonce": str(nonce) + } + return headers def request(self, method='GET', devices_or_scenes='devices', service_id='', service='', json_body=None): """ @@ -30,20 +60,20 @@ def request(self, method='GET', devices_or_scenes='devices', service_id='', serv raise ValueError('Please set devices_or_scenes variable devices or scenes') url = os.path.join(self._host_domain, devices_or_scenes, service_id, service) + + headers = self.make_request_header(self.token, self.secret) if method == 'GET': response = requests.get( url, - headers={'Authorization': self.token} + headers=headers ) elif method == 'POST': response = requests.post( url, - json_body, - headers={ - 'Content-Type': 'application/json; charset=utf8', - 'Authorization': self.token - }) + json=json_body, + headers=headers + ) else: raise ValueError('Got unexpected http request method. Please use GET or POST.') @@ -87,8 +117,8 @@ def update_device_list(self): self.infrared_remote_list = res['body']['infraredRemoteList'] for device in self.device_list: self.device_name_id[device['deviceName']] = device['deviceId'] - for infrated_remote in self.infrared_remote_list: - self.device_name_id[device['deviceName']] = device['deviceId'] + for infrared_remote in self.infrared_remote_list: + self.device_name_id[infrared_remote['deviceName']] = infrared_remote['deviceId'] return self.device_list, self.infrared_remote_list @@ -125,11 +155,11 @@ def control_device(self, command, parameter='default', command_type='command', d """ Send Command to the device. Please see https://github.com/OpenWonderLabs/SwitchBotAPI#send-device-control-commands for command options. """ - json_body = json.dumps({ - "command": command, - "parameter": parameter, - "commandType": command_type - }) + json_body = { + "command": str(command), + "parameter": str(parameter), + "commandType": str(command_type) + } if device_id: pass elif device_name: From 77343d31fa26962b2742c43c0027b344c6fcaa0e Mon Sep 17 00:00:00 2001 From: y-yosuke Date: Fri, 28 Jul 2023 19:00:12 +0900 Subject: [PATCH 03/46] mod compatibility for both API version 1.0 and 1.1 --- switchbot_ros/launch/switchbot.launch | 2 +- switchbot_ros/scripts/switchbot_ros_server.py | 58 ++++++++++++++----- switchbot_ros/src/switchbot_ros/switchbot.py | 14 +++-- 3 files changed, 54 insertions(+), 20 deletions(-) diff --git a/switchbot_ros/launch/switchbot.launch b/switchbot_ros/launch/switchbot.launch index f5644e047..188a42af8 100644 --- a/switchbot_ros/launch/switchbot.launch +++ b/switchbot_ros/launch/switchbot.launch @@ -1,6 +1,6 @@ - + Date: Sat, 29 Jul 2023 11:53:04 +0900 Subject: [PATCH 04/46] fixes for Python 2 compatibility --- switchbot_ros/src/switchbot_ros/switchbot.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/switchbot_ros/src/switchbot_ros/switchbot.py b/switchbot_ros/src/switchbot_ros/switchbot.py index 4df322047..558c03784 100644 --- a/switchbot_ros/src/switchbot_ros/switchbot.py +++ b/switchbot_ros/src/switchbot_ros/switchbot.py @@ -32,7 +32,7 @@ def __init__(self, token, secret="secret_none"): self.update_device_list() self.update_scene_list() - def make_sign(self, token: str, secret: str): + def make_sign(self, token, secret): nonce = uuid.uuid4() t = int(round(time.time() * 1000)) @@ -45,7 +45,7 @@ def make_sign(self, token: str, secret: str): return sign, str(t), nonce - def make_request_header(self, token: str, secret: str): + def make_request_header(self, token, secret): sign,t,nonce = self.make_sign(token, secret) headers={ "Authorization": token, From e5ed02b238942ccc3634b86c91f93a07bc6546bf Mon Sep 17 00:00:00 2001 From: y-yosuke Date: Tue, 1 Aug 2023 21:27:07 +0900 Subject: [PATCH 05/46] mod. requested changes: launch option secret string secret_none -> empty, print_baseurl() -> print_apiversion() and add spaces. also add descriptions about additional methods in spacebot.py. --- switchbot_ros/launch/switchbot.launch | 2 +- switchbot_ros/scripts/switchbot_ros_server.py | 8 ++++---- switchbot_ros/src/switchbot_ros/switchbot.py | 20 ++++++++++++------- 3 files changed, 18 insertions(+), 12 deletions(-) diff --git a/switchbot_ros/launch/switchbot.launch b/switchbot_ros/launch/switchbot.launch index 188a42af8..7e5a69e0b 100644 --- a/switchbot_ros/launch/switchbot.launch +++ b/switchbot_ros/launch/switchbot.launch @@ -1,6 +1,6 @@ - + Date: Tue, 1 Aug 2023 22:04:03 +0900 Subject: [PATCH 06/46] mod unmatched variable name. --- switchbot_ros/scripts/switchbot_ros_server.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/switchbot_ros/scripts/switchbot_ros_server.py b/switchbot_ros/scripts/switchbot_ros_server.py index f6deb0d54..af2e7a9b7 100755 --- a/switchbot_ros/scripts/switchbot_ros_server.py +++ b/switchbot_ros/scripts/switchbot_ros_server.py @@ -73,9 +73,9 @@ def print_apiversion(self): if self.bots is None: return - base_url_str = 'Using SwitchBot API '; - base_url_str += self.bots.api_version; - rospy.loginfo(base_url_str) + apiversion_str = 'Using SwitchBot API '; + apiversion_str += self.bots.api_version; + rospy.loginfo(apiversion_str) def print_devices(self): From 429cd88063ae3b2785f682388c4939607b507d73 Mon Sep 17 00:00:00 2001 From: y-yosuke Date: Wed, 9 Aug 2023 16:03:51 +0900 Subject: [PATCH 07/46] mod a space, an if-else condition and python 2-3 compativility. --- switchbot_ros/scripts/switchbot_ros_server.py | 8 ++++---- switchbot_ros/src/switchbot_ros/switchbot.py | 16 ++++++++++++---- 2 files changed, 16 insertions(+), 8 deletions(-) diff --git a/switchbot_ros/scripts/switchbot_ros_server.py b/switchbot_ros/scripts/switchbot_ros_server.py index af2e7a9b7..b20262ac9 100755 --- a/switchbot_ros/scripts/switchbot_ros_server.py +++ b/switchbot_ros/scripts/switchbot_ros_server.py @@ -28,9 +28,9 @@ def __init__(self): self.token = token # Switchbot API v1.1 needs secret key - secret = rospy.get_param('~secret') - if os.path.exists(secret): - with open(secret) as f: + secret = rospy.get_param('~secret', None ) + if secret is not None and os.path.exists(secret): + with open(secret, 'r', encoding='utf-8') as f: self.secret = f.read().replace('\n', '') else: self.secret = secret @@ -162,7 +162,7 @@ def execute_cb(self, goal): command_type = 'command' try: if not self.bots: - self.bots = SwitchBotAPIClient(token=self.token,secret=self.secret) + self.bots = SwitchBotAPIClient(token=self.token, secret=self.secret) feedback.status = str( self.bots.control_device( command=goal.command, diff --git a/switchbot_ros/src/switchbot_ros/switchbot.py b/switchbot_ros/src/switchbot_ros/switchbot.py index 6a1e6d5e6..7468774a2 100644 --- a/switchbot_ros/src/switchbot_ros/switchbot.py +++ b/switchbot_ros/src/switchbot_ros/switchbot.py @@ -4,6 +4,7 @@ import os.path import requests +import sys import os import time import hashlib @@ -41,11 +42,18 @@ def make_sign(self, token, secret): t = int(round(time.time() * 1000)) string_to_sign = '{}{}{}'.format(token, t, nonce) - string_to_sign = bytes(string_to_sign, 'utf-8') - secret = bytes(secret, 'utf-8') + if sys.version_info[0] > 2: + string_to_sign = bytes(string_to_sign, 'utf-8') + secret = bytes(secret, 'utf-8') + else: + string_to_sign = bytes(string_to_sign) + secret = bytes(secret) sign = base64.b64encode(hmac.new(secret, msg=string_to_sign, digestmod=hashlib.sha256).digest()) - + + if sys.version_info[0] > 2: + sign = sign.decode('utf-8') + return sign, str(t), nonce def make_request_header(self, token, secret): @@ -55,7 +63,7 @@ def make_request_header(self, token, secret): sign, t, nonce = self.make_sign(token, secret) headers={ "Authorization": token, - "sign": str(sign, 'utf-8'), + "sign": str(sign), "t": str(t), "nonce": str(nonce), "Content-Type": "application/json; charset=utf8" From f925bc2c70f478e5ee9398a52c16d1ed0964485e Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Mon, 23 Oct 2023 11:52:31 +0900 Subject: [PATCH 08/46] [switchbot_ros]force to use python3 for lambda string sort --- switchbot_ros/CMakeLists.txt | 6 ++++++ switchbot_ros/package.xml | 7 +++---- switchbot_ros/scripts/switchbot_ros_server.py | 0 3 files changed, 9 insertions(+), 4 deletions(-) mode change 100755 => 100644 switchbot_ros/scripts/switchbot_ros_server.py diff --git a/switchbot_ros/CMakeLists.txt b/switchbot_ros/CMakeLists.txt index e5426bb6a..9cdd6c183 100644 --- a/switchbot_ros/CMakeLists.txt +++ b/switchbot_ros/CMakeLists.txt @@ -5,6 +5,7 @@ find_package( catkin REQUIRED COMPONENTS message_generation actionlib_msgs + catkin_virtualenv ) catkin_python_setup() @@ -27,6 +28,11 @@ generate_messages( catkin_package() +catkin_generate_virtualenv( + PYTHON_INTERPRETER python3 + CHECK_VENV FALSE +) + include_directories() # install diff --git a/switchbot_ros/package.xml b/switchbot_ros/package.xml index 9aa05e990..0414d05f2 100644 --- a/switchbot_ros/package.xml +++ b/switchbot_ros/package.xml @@ -11,15 +11,14 @@ BSD catkin - python-setuptools - python3-setuptools + python3-setuptools actionlib actionlib_msgs + catkin_virtualenv message_generation - python-requests - python3-requests + python3-requests actionlib actionlib_msgs message_runtime diff --git a/switchbot_ros/scripts/switchbot_ros_server.py b/switchbot_ros/scripts/switchbot_ros_server.py old mode 100755 new mode 100644 From be1e1057120b52d04c05d1a575715a01bc59e189 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Fri, 27 Oct 2023 11:00:48 +0900 Subject: [PATCH 09/46] relax failed test dialogflow_task_executive, julius_ros --- dialogflow_task_executive/test/test_rospy_node.py | 12 ++++++++---- dialogflow_task_executive/test/test_rospy_node.test | 2 +- julius_ros/test/julius.test | 2 +- 3 files changed, 10 insertions(+), 6 deletions(-) diff --git a/dialogflow_task_executive/test/test_rospy_node.py b/dialogflow_task_executive/test/test_rospy_node.py index 318d6c8d6..a56f75054 100644 --- a/dialogflow_task_executive/test/test_rospy_node.py +++ b/dialogflow_task_executive/test/test_rospy_node.py @@ -27,11 +27,15 @@ def test_rosnode(self): full_scripts_dir = os.path.join(pkg_dir, scripts_dir) if not os.path.exists(full_scripts_dir): continue - for filename in [f for f in map(lambda x: os.path.join(full_scripts_dir, x), os.listdir(full_scripts_dir)) if os.path.isfile(f) and f.endswith('.py')]: + for filename in [f for f in map(lambda x: x, os.listdir(full_scripts_dir)) if os.path.isfile(f) and f.endswith('.py')]: print("Check if {} is loadable".format(filename)) - # https://stackoverflow.com/questions/4484872/why-doesnt-exec-work-in-a-function-with-a-subfunction - exec(open(filename, encoding='utf-8').read()) in globals(), locals() - self.assertTrue(True) + import subprocess + try: + ret = subprocess.check_output(['rosrun', pkg_name, filename], stderr=subprocess.STDOUT) + except subprocess.CalledProcessError as e: + print("Catch runtime error ({}), check if this is expect".format(e.output)) + self.assertTrue('Check the device is connected and recognized' in e.output) + if __name__ == '__main__': rostest.rosrun('test_rospy_node', pkg_name, TestRospyNode, sys.argv) diff --git a/dialogflow_task_executive/test/test_rospy_node.test b/dialogflow_task_executive/test/test_rospy_node.test index e47acaf68..c692f54ca 100644 --- a/dialogflow_task_executive/test/test_rospy_node.test +++ b/dialogflow_task_executive/test/test_rospy_node.test @@ -1,3 +1,3 @@ - + diff --git a/julius_ros/test/julius.test b/julius_ros/test/julius.test index 06cfce3b1..361fc0259 100644 --- a/julius_ros/test/julius.test +++ b/julius_ros/test/julius.test @@ -15,7 +15,7 @@ - + dnn: $(arg dnn) From 9b679dbadc5353c764a4c66ee97a5d9f9b9c5eb5 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Mon, 30 Oct 2023 10:18:38 +0900 Subject: [PATCH 10/46] run with -j2/-j8 for arm compile --- .github/workflows/config.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/config.yml b/.github/workflows/config.yml index 223614529..1fdc57c70 100644 --- a/.github/workflows/config.yml +++ b/.github/workflows/config.yml @@ -149,14 +149,14 @@ jobs: export EXTRA_DEB=${{ matrix.EXTRA_DEB }} export ROS_DISTRO=${{ matrix.ROS_DISTRO }} export ROS_PARALLEL_TEST_JOBS="-j2" - export CATKIN_PARALLEL_JOBS="-i" + export CATKIN_PARALLEL_JOBS="-i -j2" export ROSDEP_ADDITIONAL_OPTIONS="-n -q -r --ignore-src --skip-keys=python-google-cloud-texttospeech-pip --skip-keys=python-dialogflow-pip" # Skip installation of grpcio by pip because it causes error export BEFORE_SCRIPT="sudo pip install virtualenv==15.1.0" export USE_TRAVIS=true export USE_DOCKER=false export DOCKER_IMAGE=${{ matrix.CONTAINER }} export NOT_TEST_INSTALL=true - export ROS_PARALLEL_JOBS="--make-args LANG=C.UTF-8 LC_ALL=C.UTF-8" + export ROS_PARALLEL_JOBS="-j8 --make-args LANG=C.UTF-8 LC_ALL=C.UTF-8" set +o nounset export CI_SOURCE_PATH=$(pwd) From 81d50d537c574c1f6c5dbf791d2b7361bb1def51 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Mon, 6 Nov 2023 18:45:43 +0900 Subject: [PATCH 11/46] requirements.in.noetic: add 'grpcio==1.54.0', arm64v8 requires this line --- dialogflow_task_executive/requirements.in.noetic | 1 + 1 file changed, 1 insertion(+) diff --git a/dialogflow_task_executive/requirements.in.noetic b/dialogflow_task_executive/requirements.in.noetic index 7fe2d496f..63615e454 100644 --- a/dialogflow_task_executive/requirements.in.noetic +++ b/dialogflow_task_executive/requirements.in.noetic @@ -3,3 +3,4 @@ google-api-core[grpc]==1.33.0 grpcio-status==1.48.1 googleapis-common-protos[grpc]==1.56.2 protobuf==3.20.1 # fix Could not find a version that matches protobuf<4.0.0dev,<5.0.0dev,>=3.15.0,>=3.20.1,>=4.21.3 (from google-api-core[grpc]==1.33.1->dialogflow==1.1.1->-r requirements.in (line 1)) +grpcio==1.54.0 # via google-api-core, googleapis-common-protos, grpcio-status From 3e019d20c2ecb061043b99aab5f21fb6f52776a6 Mon Sep 17 00:00:00 2001 From: YUKINA-3252 Date: Thu, 16 Nov 2023 13:50:48 +0900 Subject: [PATCH 12/46] fix typo in jsk_3rdparty/ros_speech_recognition/README.md --- ros_speech_recognition/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros_speech_recognition/README.md b/ros_speech_recognition/README.md index ec116f7df..fba1d1dc2 100644 --- a/ros_speech_recognition/README.md +++ b/ros_speech_recognition/README.md @@ -41,7 +41,7 @@ roslaunch ros_speech_recognition parrotry.launch language:=ja-JP ### Publishing Topics -* `~voice_topic` (`sound_recognition_msgs/SpeechReconitionCandidates`) +* `~voice_topic` (`speech_recognition_msgs/SpeechRecognitionCandidates`) Speech recognition candidates topic name. From d7b924ae2d1a6af11df9929994b7f6571730e1a5 Mon Sep 17 00:00:00 2001 From: Yosuke Yamamoto Date: Wed, 13 Mar 2024 17:45:12 +0900 Subject: [PATCH 13/46] 1st commit for adding switchbot_status_publisher. --- .../scripts/switchbot_state_publisher.py | 202 ++++++++++++++++++ .../src/switchbot_ros/switchbot_ros_client.py | 2 + 2 files changed, 204 insertions(+) create mode 100644 switchbot_ros/scripts/switchbot_state_publisher.py diff --git a/switchbot_ros/scripts/switchbot_state_publisher.py b/switchbot_ros/scripts/switchbot_state_publisher.py new file mode 100644 index 000000000..d1cf4e740 --- /dev/null +++ b/switchbot_ros/scripts/switchbot_state_publisher.py @@ -0,0 +1,202 @@ +#!/usr/bin/env python + +# import actionlib +import os.path +from requests import ConnectionError +import rospy +# from switchbot_ros.msg import SwitchBotCommandAction +# from switchbot_ros.msg import SwitchBotCommandFeedback +# from switchbot_ros.msg import SwitchBotCommandResult +from switchbot_ros.msg import Device +from switchbot_ros.msg import DeviceArray +from switchbot_ros.switchbot import SwitchBotAPIClient +from switchbot_ros.switchbot import DeviceError, SwitchBotAPIError + + +class SwitchBotStatePublisher: + """ + Publissh your switchbot status with ROS and SwitchBot API + """ + def __init__(self): + # SwitchBot configs + # '~token' can be file path or raw characters + token = rospy.get_param('~token') + if os.path.exists(token): + with open(token) as f: + self.token = f.read().replace('\n', '') + else: + self.token = token + + # Switchbot API v1.1 needs secret key + secret = rospy.get_param('~secret', None ) + if secret is not None and os.path.exists(secret): + with open(secret, 'r', encoding='utf-8') as f: + self.secret = f.read().replace('\n', '') + else: + self.secret = secret + + # Initialize switchbot client + self.bots = self.get_switchbot_client() + self.print_apiversion() + self.print_devices() + self.print_scenes() +# # Actionlib +# self._as = actionlib.SimpleActionServer( +# '~switch', SwitchBotCommandAction, +# execute_cb=self.execute_cb, auto_start=False) +# self._as.start() + # Topic + self.pub = rospy.Publisher('~devices', DeviceArray, queue_size=1, latch=True) + self.published = False + +# self.status_publisher_list = [][] + self.status_pub = rospy.Publisher('~device_name/temperature', Temperature, queue_size=1, latch=True) + + rospy.loginfo('Ready.') + + def get_switchbot_client(self): + try: + client = SwitchBotAPIClient(token=self.token, secret=self.secret) + rospy.loginfo('Switchbot API Client initialized.') + return client + except ConnectionError: # If the machine is not connected to the internet + rospy.logwarn_once('Failed to connect to the switchbot server. The client would try connecting to it when subscribes the ActionGoal topic.') + return None + + def spin(self): + rate = rospy.Rate(1) + while not rospy.is_shutdown(): + rate.sleep() + if self.bots is None: + self.bots = self.get_switchbot_client() + elif not self.published: + self.publish_devices() + self.published = True + self.get_status() + + def get_status(self): + if self.bots is None: + return + + + + + def print_apiversion(self): + if self.bots is None: + return + + apiversion_str = 'Using SwitchBot API '; + apiversion_str += self.bots.api_version; + rospy.loginfo(apiversion_str) + + + def print_devices(self): + if self.bots is None: + return + + device_list_str = 'Switchbot Device List:\n' + device_list = sorted( + self.bots.device_list, + key=lambda device: str(device.get('deviceName'))) + device_list_str += str(len(device_list)) + ' Item(s)\n' + for device in device_list: + device_list_str += 'deviceName: ' + str(device.get('deviceName')) + device_list_str += ', deviceID: ' + str(device.get('deviceId')) + device_list_str += ', deviceType: ' + str(device.get('deviceType')) + device_list_str += '\n' + rospy.loginfo(device_list_str) + + remote_list_str = 'Switchbot Remote List:\n' + infrared_remote_list = sorted( + self.bots.infrared_remote_list, + key=lambda infrared_remote: str(infrared_remote.get('deviceName'))) + remote_list_str += str(len(infrared_remote_list)) + ' Item(s)\n' + for infrared_remote in infrared_remote_list: + remote_list_str += 'deviceName: ' + str(infrared_remote.get('deviceName')) + remote_list_str += ', deviceID: ' + str(infrared_remote.get('deviceId')) + remote_list_str += ', remoteType: ' + str(infrared_remote.get('remoteType')) + remote_list_str += '\n' + rospy.loginfo(remote_list_str) + + + def print_scenes(self): + if self.bots is None: + return + + scene_list_str = 'Switchbot Scene List:\n' + scene_list = sorted( + self.bots.scene_list, + key=lambda scene: str(scene.get('sceneName'))) + scene_list_str += str(len(scene_list)) + ' Item(s)\n' + for scene in scene_list: + scene_list_str += 'sceneName: ' + str(scene.get('sceneName')) + scene_list_str += ', sceneID: ' + str(scene.get('sceneId')) + scene_list_str += '\n' + rospy.loginfo(scene_list_str) + + + def publish_devices(self): + if self.bots is None: + return + + msg = DeviceArray() + + device_list = sorted( + self.bots.device_list, + key=lambda device: str(device.get('deviceName'))) + for device in device_list: + msg_device = Device() + msg_device.name = str(device.get('deviceName')) + msg_device.type = str(device.get('deviceType')) + msg.devices.append(msg_device) + + infrared_remote_list = sorted( + self.bots.infrared_remote_list, + key=lambda infrared_remote: str(infrared_remote.get('deviceName'))) + for infrared_remote in infrared_remote_list: + msg_device = Device() + msg_device.name = str(infrared_remote.get('deviceName')) + msg_device.type = str(infrared_remote.get('remoteType')) + msg.devices.append(msg_device) + + self.pub.publish(msg) + + def execute_cb(self, goal): + feedback = SwitchBotCommandFeedback() + result = SwitchBotCommandResult() + r = rospy.Rate(1) + success = True + # start executing the action + parameter, command_type = goal.parameter, goal.command_type + if not parameter: + parameter = 'default' + if not command_type: + command_type = 'command' + try: + if not self.bots: + self.bots = SwitchBotAPIClient(token=self.token, secret=self.secret) + feedback.status = str( + self.bots.control_device( + command=goal.command, + parameter=parameter, + command_type=command_type, + device_name=goal.device_name + )) + except (DeviceError, SwitchBotAPIError, KeyError) as e: + rospy.logerr(str(e)) + feedback.status = str(e) + success = False + finally: + self._as.publish_feedback(feedback) + r.sleep() + result.done = success + self._as.set_succeeded(result) + + +if __name__ == '__main__': + try: + rospy.init_node('switchbot_state_publisher') + ssp = SwitchBotAction() + ssp.spin() + except rospy.ROSInterruptException: + pass diff --git a/switchbot_ros/src/switchbot_ros/switchbot_ros_client.py b/switchbot_ros/src/switchbot_ros/switchbot_ros_client.py index cd1b8a8d8..9119c075a 100644 --- a/switchbot_ros/src/switchbot_ros/switchbot_ros_client.py +++ b/switchbot_ros/src/switchbot_ros/switchbot_ros_client.py @@ -17,6 +17,8 @@ def __init__(self, actionname, SwitchBotCommandAction ) + rospy.loginfo("Waiting for action server to start.") + self.action_client.wait_for_server() def get_devices(self, timeout=None): From 07a016426a63abb83f99a6605190b30843d8ee24 Mon Sep 17 00:00:00 2001 From: Yosuke Yamamoto Date: Thu, 14 Mar 2024 16:08:44 +0900 Subject: [PATCH 14/46] add processes to publish SwitchBot device status with Bot, Hub 2, Meter, StripLight. --- switchbot_ros/CMakeLists.txt | 5 + switchbot_ros/launch/switchbot.launch | 15 ++ switchbot_ros/msg/Bot.msg | 6 + switchbot_ros/msg/Hub2.msg | 6 + switchbot_ros/msg/Meter.msg | 5 + switchbot_ros/msg/PlugMini.msg | 7 + switchbot_ros/msg/StripLight.msg | 6 + .../scripts/switchbot_state_publisher.py | 243 ++++++++---------- 8 files changed, 161 insertions(+), 132 deletions(-) create mode 100644 switchbot_ros/msg/Bot.msg create mode 100644 switchbot_ros/msg/Hub2.msg create mode 100644 switchbot_ros/msg/Meter.msg create mode 100644 switchbot_ros/msg/PlugMini.msg create mode 100644 switchbot_ros/msg/StripLight.msg diff --git a/switchbot_ros/CMakeLists.txt b/switchbot_ros/CMakeLists.txt index 9cdd6c183..176f91733 100644 --- a/switchbot_ros/CMakeLists.txt +++ b/switchbot_ros/CMakeLists.txt @@ -14,6 +14,11 @@ add_message_files( FILES Device.msg DeviceArray.msg + Meter.msg + PlugMini.msg + Hub2.msg + Bot.msg + StripLight.msg ) add_action_files( diff --git a/switchbot_ros/launch/switchbot.launch b/switchbot_ros/launch/switchbot.launch index 7e5a69e0b..7351e01d4 100644 --- a/switchbot_ros/launch/switchbot.launch +++ b/switchbot_ros/launch/switchbot.launch @@ -2,6 +2,9 @@ + + + @@ -10,4 +13,16 @@ secret: $(arg secret) + + + + token: $(arg token) + secret: $(arg secret) + device_name: $(arg pub_device_name) + rate: $(arg pub_status_rate) + + + diff --git a/switchbot_ros/msg/Bot.msg b/switchbot_ros/msg/Bot.msg new file mode 100644 index 000000000..92befda69 --- /dev/null +++ b/switchbot_ros/msg/Bot.msg @@ -0,0 +1,6 @@ +Header header # timestamp + +float64 battery # the current battery level, 0-100 + +string power # ON/OFF state +string device_mode # pressMode, switchMode, or customizeMode diff --git a/switchbot_ros/msg/Hub2.msg b/switchbot_ros/msg/Hub2.msg new file mode 100644 index 000000000..dfdf40b4f --- /dev/null +++ b/switchbot_ros/msg/Hub2.msg @@ -0,0 +1,6 @@ +Header header # timestamp + +float64 temperature # temperature in celsius +float64 humidity # humidity percentage + +int64 light_level # the level of illuminance of the ambience light, 1~20 diff --git a/switchbot_ros/msg/Meter.msg b/switchbot_ros/msg/Meter.msg new file mode 100644 index 000000000..df731f552 --- /dev/null +++ b/switchbot_ros/msg/Meter.msg @@ -0,0 +1,5 @@ +Header header # timestamp + +float64 temperature # temperature in celsius +float64 humidity # humidity percentage +float64 battery # the current battery level, 0-100 diff --git a/switchbot_ros/msg/PlugMini.msg b/switchbot_ros/msg/PlugMini.msg new file mode 100644 index 000000000..e74b320d0 --- /dev/null +++ b/switchbot_ros/msg/PlugMini.msg @@ -0,0 +1,7 @@ +Header header # timestamp + +float64 voltage # the voltage of the device, measured in Volt +float64 weight # the power consumed in a day, measured in Watts +float64 current # the current of the device at the moment, measured in Amp + +int32 minutes_day # he duration that the device has been used during a day, measured in minutes diff --git a/switchbot_ros/msg/StripLight.msg b/switchbot_ros/msg/StripLight.msg new file mode 100644 index 000000000..6fa8378ae --- /dev/null +++ b/switchbot_ros/msg/StripLight.msg @@ -0,0 +1,6 @@ +Header header # timestamp + +string power # ON/OFF state +string color # the color value, RGB "255:255:255" + +int64 brightness # the brightness value, range from 1 to 100 diff --git a/switchbot_ros/scripts/switchbot_state_publisher.py b/switchbot_ros/scripts/switchbot_state_publisher.py index d1cf4e740..f52adae54 100644 --- a/switchbot_ros/scripts/switchbot_state_publisher.py +++ b/switchbot_ros/scripts/switchbot_state_publisher.py @@ -1,16 +1,11 @@ #!/usr/bin/env python -# import actionlib import os.path from requests import ConnectionError import rospy -# from switchbot_ros.msg import SwitchBotCommandAction -# from switchbot_ros.msg import SwitchBotCommandFeedback -# from switchbot_ros.msg import SwitchBotCommandResult -from switchbot_ros.msg import Device -from switchbot_ros.msg import DeviceArray from switchbot_ros.switchbot import SwitchBotAPIClient from switchbot_ros.switchbot import DeviceError, SwitchBotAPIError +from switchbot_ros.msg import Meter, PlugMini, Hub2, Bot, StripLight class SwitchBotStatePublisher: @@ -38,21 +33,65 @@ def __init__(self): # Initialize switchbot client self.bots = self.get_switchbot_client() self.print_apiversion() - self.print_devices() - self.print_scenes() -# # Actionlib -# self._as = actionlib.SimpleActionServer( -# '~switch', SwitchBotCommandAction, -# execute_cb=self.execute_cb, auto_start=False) -# self._as.start() - # Topic - self.pub = rospy.Publisher('~devices', DeviceArray, queue_size=1, latch=True) - self.published = False -# self.status_publisher_list = [][] - self.status_pub = rospy.Publisher('~device_name/temperature', Temperature, queue_size=1, latch=True) + # Get parameters for publishing + self.rate = rospy.get_param('~rate', 0.1) + rospy.loginfo('Rate: ' + str(self.rate)) - rospy.loginfo('Ready.') + device_name = rospy.get_param('~device_name') + if device_name: + self.device_name = device_name + else: + rospy.logerr('None Device Name') + return + + self.device_type = None + self.device_list = sorted( + self.bots.device_list, + key=lambda device: str(device.get('deviceName'))) + for device in self.device_list: + device_name = str(device.get('deviceName')) + if self.device_name == device_name: + self.device_type = str(device.get('deviceType')) + + if self.device_type: + rospy.loginfo('deviceName: ' + self.device_name + ' / deviceType: ' + self.device_type) + else: + rospy.logerr('Invalid Device Name: ' + self.device_name) + return + + topic_name = '~' + self.device_name + topic_name = topic_name.replace('-', '_') + + # Publisher for each device type + if self.device_type == 'Remote': + rospy.logerr('Device Type: "' + self.device_type + '" has no status.') + return + else: + if self.device_type == 'Meter': + self.msg_class = Meter + elif self.device_type == 'MeterPlus': + self.msg_class = Meter + elif self.device_type == 'WoIOSensor': + self.msg_class = Meter + elif self.device_type == 'Hub 2': + self.msg_class = Hub2 + elif self.device_type == 'Plug Mini (JP)': + self.msg_class = PlugMini + elif self.device_type == 'Plug Mini (US)': + self.msg_class = PlugMini + elif self.device_type == 'Bot': + self.msg_class = Bot + elif self.device_type == 'Strip Light': + self.msg_class = StripLight + else: + rospy.logerr('No publisher process for "' + self.device_type + '" in switchbot_state_publisher.py') + return + + self.status_pub = rospy.Publisher(topic_name, self.msg_class, queue_size=1, latch=True) + + rospy.loginfo('Ready: SwitchBot Status Publisher for ' + self.device_name) + def get_switchbot_client(self): try: @@ -63,23 +102,66 @@ def get_switchbot_client(self): rospy.logwarn_once('Failed to connect to the switchbot server. The client would try connecting to it when subscribes the ActionGoal topic.') return None + def spin(self): - rate = rospy.Rate(1) + rate = rospy.Rate(self.rate) while not rospy.is_shutdown(): rate.sleep() if self.bots is None: self.bots = self.get_switchbot_client() - elif not self.published: - self.publish_devices() - self.published = True - self.get_status() + + if not self.device_type == 'Remote': + status = self.get_device_status(device_name=self.device_name) + + if status: + time = rospy.get_rostime() + if self.msg_class == Meter: + msg = Meter() + msg.header.stamp = time + msg.temperature = status['temperature'] + msg.humidity = status['humidity'] + msg.battery = status['battery'] + elif self.msg_class == Hub2: + msg = Hub2() + msg.header.stamp = time + msg.temperature = status['temperature'] + msg.humidity = status['humidity'] + msg.light_level = status['lightLevel'] + elif self.msg_class == PlugMini: + msg = PlugMini() + msg.header.stamp = time + msg.voltage = status['voltage'] + msg.weight = status['weight'] + msg.current = status['electricCurrent'] + msg.minutes_day = status['electricityOfDay'] + elif self.msg_class == Bot: + msg = Bot() + msg.header.stamp = time + msg.battery = status['battery'] + msg.power = status['power'] + msg.device_mode = status['deviceMode'] + elif self.msg_class == StripLight: + msg = StripLight() + msg.header.stamp = time + msg.power = status['power'] + msg.color = status['color'] + msg.brightness = status['brightness'] + else: + return + + if msg: + self.status_pub.publish(msg) + - def get_status(self): + def get_device_status(self, device_name=None): if self.bots is None: return - - - + elif device_name: + status = self.bots.device_status(device_name=device_name) + return status + else: + return + def print_apiversion(self): if self.bots is None: @@ -88,115 +170,12 @@ def print_apiversion(self): apiversion_str = 'Using SwitchBot API '; apiversion_str += self.bots.api_version; rospy.loginfo(apiversion_str) - - - def print_devices(self): - if self.bots is None: - return - - device_list_str = 'Switchbot Device List:\n' - device_list = sorted( - self.bots.device_list, - key=lambda device: str(device.get('deviceName'))) - device_list_str += str(len(device_list)) + ' Item(s)\n' - for device in device_list: - device_list_str += 'deviceName: ' + str(device.get('deviceName')) - device_list_str += ', deviceID: ' + str(device.get('deviceId')) - device_list_str += ', deviceType: ' + str(device.get('deviceType')) - device_list_str += '\n' - rospy.loginfo(device_list_str) - - remote_list_str = 'Switchbot Remote List:\n' - infrared_remote_list = sorted( - self.bots.infrared_remote_list, - key=lambda infrared_remote: str(infrared_remote.get('deviceName'))) - remote_list_str += str(len(infrared_remote_list)) + ' Item(s)\n' - for infrared_remote in infrared_remote_list: - remote_list_str += 'deviceName: ' + str(infrared_remote.get('deviceName')) - remote_list_str += ', deviceID: ' + str(infrared_remote.get('deviceId')) - remote_list_str += ', remoteType: ' + str(infrared_remote.get('remoteType')) - remote_list_str += '\n' - rospy.loginfo(remote_list_str) - - - def print_scenes(self): - if self.bots is None: - return - - scene_list_str = 'Switchbot Scene List:\n' - scene_list = sorted( - self.bots.scene_list, - key=lambda scene: str(scene.get('sceneName'))) - scene_list_str += str(len(scene_list)) + ' Item(s)\n' - for scene in scene_list: - scene_list_str += 'sceneName: ' + str(scene.get('sceneName')) - scene_list_str += ', sceneID: ' + str(scene.get('sceneId')) - scene_list_str += '\n' - rospy.loginfo(scene_list_str) - - - def publish_devices(self): - if self.bots is None: - return - - msg = DeviceArray() - - device_list = sorted( - self.bots.device_list, - key=lambda device: str(device.get('deviceName'))) - for device in device_list: - msg_device = Device() - msg_device.name = str(device.get('deviceName')) - msg_device.type = str(device.get('deviceType')) - msg.devices.append(msg_device) - - infrared_remote_list = sorted( - self.bots.infrared_remote_list, - key=lambda infrared_remote: str(infrared_remote.get('deviceName'))) - for infrared_remote in infrared_remote_list: - msg_device = Device() - msg_device.name = str(infrared_remote.get('deviceName')) - msg_device.type = str(infrared_remote.get('remoteType')) - msg.devices.append(msg_device) - - self.pub.publish(msg) - - def execute_cb(self, goal): - feedback = SwitchBotCommandFeedback() - result = SwitchBotCommandResult() - r = rospy.Rate(1) - success = True - # start executing the action - parameter, command_type = goal.parameter, goal.command_type - if not parameter: - parameter = 'default' - if not command_type: - command_type = 'command' - try: - if not self.bots: - self.bots = SwitchBotAPIClient(token=self.token, secret=self.secret) - feedback.status = str( - self.bots.control_device( - command=goal.command, - parameter=parameter, - command_type=command_type, - device_name=goal.device_name - )) - except (DeviceError, SwitchBotAPIError, KeyError) as e: - rospy.logerr(str(e)) - feedback.status = str(e) - success = False - finally: - self._as.publish_feedback(feedback) - r.sleep() - result.done = success - self._as.set_succeeded(result) if __name__ == '__main__': try: rospy.init_node('switchbot_state_publisher') - ssp = SwitchBotAction() + ssp = SwitchBotStatePublisher() ssp.spin() except rospy.ROSInterruptException: pass From 58f77f1cf3234595f4305416bdd53d55fb8f89e8 Mon Sep 17 00:00:00 2001 From: Yosuke Yamamoto Date: Fri, 15 Mar 2024 14:04:45 +0900 Subject: [PATCH 15/46] mod. some comments, messages and wrong writing style. --- .../scripts/switchbot_state_publisher.py | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/switchbot_ros/scripts/switchbot_state_publisher.py b/switchbot_ros/scripts/switchbot_state_publisher.py index f52adae54..11dde61af 100644 --- a/switchbot_ros/scripts/switchbot_state_publisher.py +++ b/switchbot_ros/scripts/switchbot_state_publisher.py @@ -23,7 +23,7 @@ def __init__(self): self.token = token # Switchbot API v1.1 needs secret key - secret = rospy.get_param('~secret', None ) + secret = rospy.get_param('~secret', None) if secret is not None and os.path.exists(secret): with open(secret, 'r', encoding='utf-8') as f: self.secret = f.read().replace('\n', '') @@ -42,13 +42,13 @@ def __init__(self): if device_name: self.device_name = device_name else: - rospy.logerr('None Device Name') + rospy.logerr('No Device Name') return - self.device_type = None + self.device_type = None self.device_list = sorted( self.bots.device_list, - key=lambda device: str(device.get('deviceName'))) + key=lambda device: str(device.get('deviceName'))) for device in self.device_list: device_name = str(device.get('deviceName')) if self.device_name == device_name: @@ -63,9 +63,9 @@ def __init__(self): topic_name = '~' + self.device_name topic_name = topic_name.replace('-', '_') - # Publisher for each device type + # Publisher Message Class for each device type if self.device_type == 'Remote': - rospy.logerr('Device Type: "' + self.device_type + '" has no status.') + rospy.logerr('Device Type: "' + self.device_type + '" has no status in specifications.') return else: if self.device_type == 'Meter': @@ -110,7 +110,9 @@ def spin(self): if self.bots is None: self.bots = self.get_switchbot_client() - if not self.device_type == 'Remote': + if self.device_type == 'Remote': + return + else: status = self.get_device_status(device_name=self.device_name) if status: @@ -151,7 +153,7 @@ def spin(self): if msg: self.status_pub.publish(msg) - + def get_device_status(self, device_name=None): if self.bots is None: From 78c3633d636534ca18f89d7aecff8aa1917497ec Mon Sep 17 00:00:00 2001 From: Yosuke Yamamoto Date: Mon, 18 Mar 2024 14:59:41 +0900 Subject: [PATCH 16/46] rename ..state.. to ..status.. --- switchbot_ros/launch/switchbot.launch | 2 +- switchbot_ros/scripts/control_switchbot.py | 4 ++-- ...t_state_publisher.py => switchbot_status_publisher.py} | 8 ++++---- 3 files changed, 7 insertions(+), 7 deletions(-) rename switchbot_ros/scripts/{switchbot_state_publisher.py => switchbot_status_publisher.py} (97%) diff --git a/switchbot_ros/launch/switchbot.launch b/switchbot_ros/launch/switchbot.launch index 7351e01d4..db57da27e 100644 --- a/switchbot_ros/launch/switchbot.launch +++ b/switchbot_ros/launch/switchbot.launch @@ -15,7 +15,7 @@ token: $(arg token) diff --git a/switchbot_ros/scripts/control_switchbot.py b/switchbot_ros/scripts/control_switchbot.py index 1c04c2b73..3dede636e 100644 --- a/switchbot_ros/scripts/control_switchbot.py +++ b/switchbot_ros/scripts/control_switchbot.py @@ -9,7 +9,7 @@ devices = client.get_devices() print(devices) -client.control_device('pendant-light', 'turnOff') +client.control_device('pendant-light', 'turnOn', wait=True) -client.control_device('bot74a', 'turnOn') +client.control_device('bot74a', 'turnOn', wait=True) diff --git a/switchbot_ros/scripts/switchbot_state_publisher.py b/switchbot_ros/scripts/switchbot_status_publisher.py similarity index 97% rename from switchbot_ros/scripts/switchbot_state_publisher.py rename to switchbot_ros/scripts/switchbot_status_publisher.py index 11dde61af..ff7e84319 100644 --- a/switchbot_ros/scripts/switchbot_state_publisher.py +++ b/switchbot_ros/scripts/switchbot_status_publisher.py @@ -8,7 +8,7 @@ from switchbot_ros.msg import Meter, PlugMini, Hub2, Bot, StripLight -class SwitchBotStatePublisher: +class SwitchBotStatusPublisher: """ Publissh your switchbot status with ROS and SwitchBot API """ @@ -85,7 +85,7 @@ def __init__(self): elif self.device_type == 'Strip Light': self.msg_class = StripLight else: - rospy.logerr('No publisher process for "' + self.device_type + '" in switchbot_state_publisher.py') + rospy.logerr('No publisher process for "' + self.device_type + '" in switchbot_status_publisher.py') return self.status_pub = rospy.Publisher(topic_name, self.msg_class, queue_size=1, latch=True) @@ -176,8 +176,8 @@ def print_apiversion(self): if __name__ == '__main__': try: - rospy.init_node('switchbot_state_publisher') - ssp = SwitchBotStatePublisher() + rospy.init_node('switchbot_status_publisher') + ssp = SwitchBotStatusPublisher() ssp.spin() except rospy.ROSInterruptException: pass From 9a0e042c558ee6a9ce0f5581357b9de20fc85ca9 Mon Sep 17 00:00:00 2001 From: Yosuke Yamamoto Date: Mon, 18 Mar 2024 15:20:03 +0900 Subject: [PATCH 17/46] change switchbot.launch default of pub_status to false. --- switchbot_ros/launch/switchbot.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/switchbot_ros/launch/switchbot.launch b/switchbot_ros/launch/switchbot.launch index db57da27e..cb9a68a96 100644 --- a/switchbot_ros/launch/switchbot.launch +++ b/switchbot_ros/launch/switchbot.launch @@ -2,7 +2,7 @@ - + From 852fe897cdf183f08182ee93e53e234b3b5e0e3f Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Thu, 28 Mar 2024 15:22:33 +0900 Subject: [PATCH 18/46] install apps/samples/config --- dialogflow_task_executive/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dialogflow_task_executive/CMakeLists.txt b/dialogflow_task_executive/CMakeLists.txt index 9e67eb43a..1717db7dd 100644 --- a/dialogflow_task_executive/CMakeLists.txt +++ b/dialogflow_task_executive/CMakeLists.txt @@ -73,7 +73,7 @@ catkin_install_python( PROGRAMS ${PYTHON_SCRIPT_FILES} DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) -install(DIRECTORY launch +install(DIRECTORY launch apps samples config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} USE_SOURCE_PERMISSIONS ) From 261c36065678b0ea0d72d5deb1e2c1c81780600a Mon Sep 17 00:00:00 2001 From: Yosuke Yamamoto Date: Tue, 16 Apr 2024 15:22:52 +0900 Subject: [PATCH 19/46] mod. messages and wait_for_server() in switchbot_ros_client.py to set timeout. --- switchbot_ros/msg/Bot.msg | 6 +++++- switchbot_ros/msg/StripLight.msg | 6 ++++-- .../scripts/switchbot_status_publisher.py | 16 +++++++++++++--- .../src/switchbot_ros/switchbot_ros_client.py | 7 ++++--- 4 files changed, 26 insertions(+), 9 deletions(-) diff --git a/switchbot_ros/msg/Bot.msg b/switchbot_ros/msg/Bot.msg index 92befda69..74955d462 100644 --- a/switchbot_ros/msg/Bot.msg +++ b/switchbot_ros/msg/Bot.msg @@ -1,6 +1,10 @@ +string DEVICEMODE_PRESS = "pressMode" +string DEVICEMODE_SWITCH = "switchMode" +string DEVICEMODE_CUSTOMIZE = "customizeMode" + Header header # timestamp float64 battery # the current battery level, 0-100 -string power # ON/OFF state +bool power # ON/OFF state True/False string device_mode # pressMode, switchMode, or customizeMode diff --git a/switchbot_ros/msg/StripLight.msg b/switchbot_ros/msg/StripLight.msg index 6fa8378ae..4164d184e 100644 --- a/switchbot_ros/msg/StripLight.msg +++ b/switchbot_ros/msg/StripLight.msg @@ -1,6 +1,8 @@ Header header # timestamp -string power # ON/OFF state -string color # the color value, RGB "255:255:255" +bool power # ON/OFF state True/False int64 brightness # the brightness value, range from 1 to 100 +int64 color_r # Red color value 0-255 +int64 color_g # Green color value 0-255 +int64 color_b # Blue color value 0-255 \ No newline at end of file diff --git a/switchbot_ros/scripts/switchbot_status_publisher.py b/switchbot_ros/scripts/switchbot_status_publisher.py index ff7e84319..6ed571728 100644 --- a/switchbot_ros/scripts/switchbot_status_publisher.py +++ b/switchbot_ros/scripts/switchbot_status_publisher.py @@ -140,14 +140,24 @@ def spin(self): msg = Bot() msg.header.stamp = time msg.battery = status['battery'] - msg.power = status['power'] + if status['power'] == 'on': + msg.power = True + else: + msg.power = False msg.device_mode = status['deviceMode'] elif self.msg_class == StripLight: msg = StripLight() msg.header.stamp = time - msg.power = status['power'] - msg.color = status['color'] + if status['power'] == 'on': + msg.power = True + else: + msg.power = False msg.brightness = status['brightness'] + rgb_string = status['color'] + r, g, b = map(int, rgb_string.split(':')) + msg.color_r = r + msg.color_g = g + msg.color_b = b else: return diff --git a/switchbot_ros/src/switchbot_ros/switchbot_ros_client.py b/switchbot_ros/src/switchbot_ros/switchbot_ros_client.py index 9119c075a..a73527b87 100644 --- a/switchbot_ros/src/switchbot_ros/switchbot_ros_client.py +++ b/switchbot_ros/src/switchbot_ros/switchbot_ros_client.py @@ -9,7 +9,8 @@ class SwitchBotROSClient(object): def __init__(self, actionname='switchbot_ros/switch', - topicname='switchbot_ros/devices'): + topicname='switchbot_ros/devices', + timeout=5): self.actionname = actionname self.topicname = topicname @@ -17,8 +18,8 @@ def __init__(self, actionname, SwitchBotCommandAction ) - rospy.loginfo("Waiting for action server to start.") - self.action_client.wait_for_server() + rospy.loginfo("Waiting " + str(timeout) + "[sec] for action server to start .") + self.action_client.wait_for_server(timeout=rospy.Duration(timeout,0)) def get_devices(self, timeout=None): From f7543840a6d59f17f3273990dbcf74c8bcaf6b7c Mon Sep 17 00:00:00 2001 From: Yosuke Yamamoto Date: Tue, 16 Apr 2024 15:34:34 +0900 Subject: [PATCH 20/46] mod. loginfo sentence in switchbot_ros_client.py --- switchbot_ros/src/switchbot_ros/switchbot_ros_client.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/switchbot_ros/src/switchbot_ros/switchbot_ros_client.py b/switchbot_ros/src/switchbot_ros/switchbot_ros_client.py index a73527b87..df1a7b00a 100644 --- a/switchbot_ros/src/switchbot_ros/switchbot_ros_client.py +++ b/switchbot_ros/src/switchbot_ros/switchbot_ros_client.py @@ -18,7 +18,7 @@ def __init__(self, actionname, SwitchBotCommandAction ) - rospy.loginfo("Waiting " + str(timeout) + "[sec] for action server to start .") + rospy.loginfo("Waiting for action server to start. (timeout: " + str(timeout) + "[sec])") self.action_client.wait_for_server(timeout=rospy.Duration(timeout,0)) def get_devices(self, timeout=None): From 3b02215e1e181b2067807e504e25db2f6788dd70 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Sat, 25 May 2024 10:14:28 +0900 Subject: [PATCH 21/46] [ros_google_cloud_language] chmod -x test_rospy_node for catkin_virtualenv --- ros_google_cloud_language/test/test_rospy_node.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) mode change 100755 => 100644 ros_google_cloud_language/test/test_rospy_node.py diff --git a/ros_google_cloud_language/test/test_rospy_node.py b/ros_google_cloud_language/test/test_rospy_node.py old mode 100755 new mode 100644 From ea8b537fe340fed9943bf8bf1d1b260e3c6cc7bc Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Tue, 9 Jul 2024 21:47:25 +0900 Subject: [PATCH 22/46] update to jsk_travis 0.5.27 --- .travis | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis b/.travis index 4e8b3cf26..b223c886b 160000 --- a/.travis +++ b/.travis @@ -1 +1 @@ -Subproject commit 4e8b3cf2637d593d05106e84edf2e4532677d37c +Subproject commit b223c886bcda0d96c6c03b0f0ae07da768a00155 From 9bf8b50d49248c54998b6c1a569fa41d04831384 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Tue, 9 Jul 2024 21:53:13 +0900 Subject: [PATCH 23/46] workaround required for checkout@v3, https://github.com/actions/checkout/issues/1590 --- .github/workflows/config.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/config.yml b/.github/workflows/config.yml index 1fdc57c70..4abc063d1 100644 --- a/.github/workflows/config.yml +++ b/.github/workflows/config.yml @@ -6,6 +6,8 @@ on: env: DISPLAY: ':0.0' + # workaround required for checkout@v3, https://github.com/actions/checkout/issues/1590 + ACTIONS_ALLOW_USE_UNSECURE_NODE_VERSION: true jobs: ros: From e8f565bba59338c725399a9ee3ae8c1b64f71520 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Wed, 10 Jul 2024 00:15:19 +0900 Subject: [PATCH 24/46] dialogflow_task_executive/gdrive_ros/respeaker_ros/ros_speech_recognition/sesame_ros/switchbot_ros: use --cert for catkin_virtualenv for indigo --- dialogflow_task_executive/CMakeLists.txt | 5 ++++- gdrive_ros/CMakeLists.txt | 10 ++++++++++ respeaker_ros/CMakeLists.txt | 7 +++++++ ros_speech_recognition/CMakeLists.txt | 11 ++++++++++- sesame_ros/CMakeLists.txt | 7 +++++++ switchbot_ros/CMakeLists.txt | 10 ++++++++++ 6 files changed, 48 insertions(+), 2 deletions(-) diff --git a/dialogflow_task_executive/CMakeLists.txt b/dialogflow_task_executive/CMakeLists.txt index 1717db7dd..f4a206208 100644 --- a/dialogflow_task_executive/CMakeLists.txt +++ b/dialogflow_task_executive/CMakeLists.txt @@ -55,7 +55,10 @@ elseif("$ENV{ROS_DISTRO}" STREQUAL "indigo") COMMAND cp ${CMAKE_CURRENT_BINARY_DIR}/requirements.txt.indigo ${CMAKE_CURRENT_SOURCE_DIR}/requirements.txt WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} ) - catkin_generate_virtualenv(PYTHON_INTERPRETER python2) + file(DOWNLOAD http://curl.haxx.se/ca/cacert.pem ${CMAKE_BINARY_DIR}/cacert.pem) + catkin_generate_virtualenv(PYTHON_INTERPRETER python2 + # https://stackoverflow.com/questions/25981703/pip-install-fails-with-connection-error-ssl-certificate-verify-failed + EXTRA_PIP_ARGS -vvv --cert=${CMAKE_BINARY_DIR}/cacert.pem) elseif("$ENV{ROS_DISTRO}" STRGREATER "melodic") catkin_generate_virtualenv( INPUT_REQUIREMENTS requirements.in.noetic diff --git a/gdrive_ros/CMakeLists.txt b/gdrive_ros/CMakeLists.txt index 68e8904bb..dab4abaef 100644 --- a/gdrive_ros/CMakeLists.txt +++ b/gdrive_ros/CMakeLists.txt @@ -23,10 +23,20 @@ catkin_package( message_runtime ) +if("$ENV{ROS_DISTRO}" STREQUAL "indigo") +file(DOWNLOAD http://curl.haxx.se/ca/cacert.pem ${CMAKE_BINARY_DIR}/cacert.pem) catkin_generate_virtualenv( PYTHON_INTERPRETER python3 CHECK_VENV FALSE + # https://stackoverflow.com/questions/25981703/pip-install-fails-with-connection-error-ssl-certificate-verify-failed + EXTRA_PIP_ARGS -vvv --cert=${CMAKE_BINARY_DIR}/cacert.pem ) +else() +catkin_generate_virtualenv( + PYTHON_INTERPRETER python3 + CHECK_VENV FALSE + ) +endif() catkin_install_python(PROGRAMS node_scripts/gdrive_server_node.py node_scripts/sample_gdrive_rospy_client.py diff --git a/respeaker_ros/CMakeLists.txt b/respeaker_ros/CMakeLists.txt index 9322760c9..d6752f005 100644 --- a/respeaker_ros/CMakeLists.txt +++ b/respeaker_ros/CMakeLists.txt @@ -19,6 +19,13 @@ if($ENV{ROS_DISTRO} STRGREATER "melodic") PYTHON_INTERPRETER python3 CHECK_VENV FALSE ) +elseif("$ENV{ROS_DISTRO}" STREQUAL "indigo") + file(DOWNLOAD http://curl.haxx.se/ca/cacert.pem ${CMAKE_BINARY_DIR}/cacert.pem) + catkin_generate_virtualenv( + PYTHON_INTERPRETER python2 + # https://stackoverflow.com/questions/25981703/pip-install-fails-with-connection-error-ssl-certificate-verify-failed + EXTRA_PIP_ARGS -vvv --cert=${CMAKE_BINARY_DIR}/cacert.pem + ) else() catkin_generate_virtualenv( PYTHON_INTERPRETER python2 diff --git a/ros_speech_recognition/CMakeLists.txt b/ros_speech_recognition/CMakeLists.txt index 9810c3377..ba2d07b93 100644 --- a/ros_speech_recognition/CMakeLists.txt +++ b/ros_speech_recognition/CMakeLists.txt @@ -29,7 +29,16 @@ if($ENV{ROS_DISTRO} STREQUAL "indigo" OR COMMAND cp ${CMAKE_CURRENT_BINARY_DIR}/requirements.txt.indigo ${CMAKE_CURRENT_SOURCE_DIR}/requirements.txt WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} ) - catkin_generate_virtualenv(PYTHON_INTERPRETER python2) + if("$ENV{ROS_DISTRO}" STREQUAL "indigo") + file(DOWNLOAD http://curl.haxx.se/ca/cacert.pem ${CMAKE_BINARY_DIR}/cacert.pem) + catkin_generate_virtualenv( + PYTHON_INTERPRETER python2 + # https://stackoverflow.com/questions/25981703/pip-install-fails-with-connection-error-ssl-certificate-verify-failed + EXTRA_PIP_ARGS -vvv --cert=${CMAKE_BINARY_DIR}/cacert.pem + ) + else() + catkin_generate_virtualenv(PYTHON_INTERPRETER python2) + endif() else() catkin_generate_virtualenv( PYTHON_INTERPRETER python3 diff --git a/sesame_ros/CMakeLists.txt b/sesame_ros/CMakeLists.txt index b154ba71a..2ff28f17e 100644 --- a/sesame_ros/CMakeLists.txt +++ b/sesame_ros/CMakeLists.txt @@ -24,6 +24,13 @@ if($ENV{ROS_DISTRO} STRGREATER "melodic") catkin_generate_virtualenv( PYTHON_INTERPRETER python3 ) +elseif("$ENV{ROS_DISTRO}" STREQUAL "indigo") + file(DOWNLOAD http://curl.haxx.se/ca/cacert.pem ${CMAKE_BINARY_DIR}/cacert.pem) + catkin_generate_virtualenv( + PYTHON_INTERPRETER python2 + # https://stackoverflow.com/questions/25981703/pip-install-fails-with-connection-error-ssl-certificate-verify-failed + EXTRA_PIP_ARGS -vvv --cert=${CMAKE_BINARY_DIR}/cacert.pem + ) else() catkin_generate_virtualenv( PYTHON_INTERPRETER python2 diff --git a/switchbot_ros/CMakeLists.txt b/switchbot_ros/CMakeLists.txt index 9cdd6c183..20160ff79 100644 --- a/switchbot_ros/CMakeLists.txt +++ b/switchbot_ros/CMakeLists.txt @@ -28,10 +28,20 @@ generate_messages( catkin_package() +if("$ENV{ROS_DISTRO}" STREQUAL "indigo") +file(DOWNLOAD http://curl.haxx.se/ca/cacert.pem ${CMAKE_BINARY_DIR}/cacert.pem) catkin_generate_virtualenv( PYTHON_INTERPRETER python3 CHECK_VENV FALSE + # https://stackoverflow.com/questions/25981703/pip-install-fails-with-connection-error-ssl-certificate-verify-failed + EXTRA_PIP_ARGS -vvv --cert=${CMAKE_BINARY_DIR}/cacert.pem ) +else() +catkin_generate_virtualenv( + PYTHON_INTERPRETER python3 + CHECK_VENV FALSE +) +endif() include_directories() From d6bdceebd7e20bf65292d3b696f638b171a1061d Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Wed, 10 Jul 2024 20:50:13 +0900 Subject: [PATCH 25/46] .travis.rosinstall.indigo: use release veresion of catkin_virtualenv to avoid test_catkin_virtualenv --- .travis.rosinstall.indigo | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.travis.rosinstall.indigo b/.travis.rosinstall.indigo index b07215c12..19545013d 100644 --- a/.travis.rosinstall.indigo +++ b/.travis.rosinstall.indigo @@ -9,5 +9,5 @@ # we need to avoid pip upgrade - git: local-name: locusrobotics/catkin_virtualenv - uri: https://github.com/locusrobotics/catkin_virtualenv - version: 0.2.2 + uri: https://github.com/locusrobotics/catkin_virtualenv-release + version: release/melodic/catkin_virtualenv/0.2.2-0 From cafbff6dd2bd7869eb4f989bedd0a322a7c35d50 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Wed, 13 Nov 2024 10:57:29 +0900 Subject: [PATCH 26/46] [libsiftfast] support multiple python3 version --- 3rdparty/libsiftfast/patches/10.boost_python38.patch | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/3rdparty/libsiftfast/patches/10.boost_python38.patch b/3rdparty/libsiftfast/patches/10.boost_python38.patch index 36dfe4c89..451fc743f 100644 --- a/3rdparty/libsiftfast/patches/10.boost_python38.patch +++ b/3rdparty/libsiftfast/patches/10.boost_python38.patch @@ -2,12 +2,14 @@ Index: CMakeLists.txt =================================================================== --- CMakeLists.txt (revision 54) +++ CMakeLists.txt (working copy) -@@ -155,7 +155,8 @@ +@@ -155,7 +155,10 @@ if( NOT $ENV{BOOST_LIBRARYDIR} STREQUAL "" ) set(Boost_LIBRARY_DIRS $ENV{BOOST_LIBRARYDIR}) endif() -find_package(Boost COMPONENTS python) -+find_package(Boost REQUIRED COMPONENTS system python38) ++set(Python3_FIND_STRATEGY VERSION) ++find_package(Python3 COMPONENTS Interpreter Development) ++find_package(Boost REQUIRED COMPONENTS system python${Python3_VERSION_MAJOR}${Python3_VERSION_MINOR}) +add_definitions("-Wno-narrowing") if( Boost_FOUND ) @@ -17,7 +19,7 @@ Index: CMakeLists.txt # set(BUILD_SIFTFASTPY) -if( Boost_PYTHON_FOUND ) -+if( Boost_PYTHON38_FOUND ) ++if( Boost_PYTHON${Python3_VERSION_MAJOR}${Python3_VERSION_MINOR}_FOUND ) find_package(PythonLibs) if( PYTHONLIBS_FOUND OR PYTHON_LIBRARIES ) From 2ef756ec27de5ff0dbeb624fc688933906bfc8c1 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Wed, 13 Nov 2024 11:00:23 +0900 Subject: [PATCH 27/46] [sesame_ros] remove cffi which cannot be installed in Ubuntu 22.04 env & not used in sesame_ros --- sesame_ros/requirements.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/sesame_ros/requirements.txt b/sesame_ros/requirements.txt index 7bb97d5c5..c76134ce7 100644 --- a/sesame_ros/requirements.txt +++ b/sesame_ros/requirements.txt @@ -1,6 +1,5 @@ asn1crypto==1.3.0 certifi==2020.6.20 -cffi==1.14.0 chardet==3.0.4 cryptography==2.3 enum34==1.1.10 From 1b9bdbdf1e1e86e28e0b6827012ea802d001b92d Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Wed, 13 Nov 2024 12:30:40 +0900 Subject: [PATCH 28/46] [ff] relax linker. allow function duplication --- 3rdparty/ff/Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/3rdparty/ff/Makefile b/3rdparty/ff/Makefile index 3a7de76b4..b691ceb70 100644 --- a/3rdparty/ff/Makefile +++ b/3rdparty/ff/Makefile @@ -16,7 +16,7 @@ MAKE_ARGS = ADDONS=-DYY_SKIP_YYWRAP installed:$(SOURCE_DIR)/unpacked rm -f $(SOURCE_DIR)/ff - (cd $(SOURCE_DIR) && $(MAKE) clean && $(MAKE) CFLAGS='-O6 -g -ansi -Wno-array-bounds -Wno-endif-labels -Wno-format-overflow -Wno-implicit-function-declaration -Wno-int-in-bool-context -Wno-unused-function -Wno-unused-variable -fno-builtin-strncpy -fno-builtin-strcpy -fno-builtin-strlen -fno-builtin-strcat -fno-builtin-memset ' $(MAKE_ARGS)) + (cd $(SOURCE_DIR) && $(MAKE) clean && $(MAKE) CFLAGS='-O6 -g -ansi -Wno-array-bounds -Wno-endif-labels -Wno-format-overflow -Wno-implicit-function-declaration -Wno-int-in-bool-context -Wno-unused-function -Wno-unused-variable -fno-builtin-strncpy -fno-builtin-strcpy -fno-builtin-strlen -fno-builtin-strcat -fno-builtin-memset -fcommon ' $(MAKE_ARGS)) mkdir -p bin cp $(SOURCE_DIR)/ff bin/ touch installed From e9cdcb687ac29133f2a36dcbcbd1330db00f3963 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Wed, 13 Nov 2024 12:32:13 +0900 Subject: [PATCH 29/46] [ffha] relax linker. allow function duplication --- 3rdparty/ffha/Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/3rdparty/ffha/Makefile b/3rdparty/ffha/Makefile index 9c6a1168c..b2d063231 100644 --- a/3rdparty/ffha/Makefile +++ b/3rdparty/ffha/Makefile @@ -22,7 +22,7 @@ $(SOURCE_DIR)/patched:$(SOURCE_DIR)/unpacked touch $(SOURCE_DIR)/patched installed:$(SOURCE_DIR)/patched - (cd $(SOURCE_DIR) && $(MAKE) clean && $(MAKE) CFLAGS='-O6 -g -ansi -Wno-array-bounds -Wno-endif-labels -Wno-format-overflow -Wno-implicit-function-declaration -Wno-int-in-bool-context -Wno-unused-function -Wno-unused-variable -fno-builtin-strncpy -fno-builtin-strcpy -fno-builtin-strlen -fno-builtin-strcat -fno-builtin-memset ' $(MAKE_ARGS)) + (cd $(SOURCE_DIR) && $(MAKE) clean && $(MAKE) CFLAGS='-O6 -g -ansi -Wno-array-bounds -Wno-endif-labels -Wno-format-overflow -Wno-implicit-function-declaration -Wno-int-in-bool-context -Wno-unused-function -Wno-unused-variable -fno-builtin-strncpy -fno-builtin-strcpy -fno-builtin-strlen -fno-builtin-strcat -fno-builtin-memset -fcommon ' $(MAKE_ARGS)) mkdir -p bin cp $(SOURCE_DIR)/ffha bin/ touch installed From e80e23ea5231e15b75823dac216beb8ee1d9c15a Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Wed, 13 Nov 2024 13:28:09 +0900 Subject: [PATCH 30/46] [downward] patching to fix std::vector namespace --- 3rdparty/downward/CMakeLists.txt | 2 +- 3rdparty/downward/fix_std_vector_namespace.patch | 10 ++++++++++ 2 files changed, 11 insertions(+), 1 deletion(-) create mode 100644 3rdparty/downward/fix_std_vector_namespace.patch diff --git a/3rdparty/downward/CMakeLists.txt b/3rdparty/downward/CMakeLists.txt index 5d153d878..ae19b0264 100644 --- a/3rdparty/downward/CMakeLists.txt +++ b/3rdparty/downward/CMakeLists.txt @@ -14,7 +14,7 @@ externalproject_add(downward URL http://cdn.rawgit.com/jsk-ros-pkg/archives/master/Fast-Downward-f33d3b65601f.tar.gz TIMEOUT 120 CONFIGURE_COMMAND "" - BUILD_COMMAND cd src && sed -i "s@^CXXFLAGS =$@CXXFLAGS = ${CXXFLAGS_NOETIC} -Wno-maybe-uninitialized@" search/Makefile && ./build_all DOWNWARD_BITWIDTH=native && patch -p3 < ${PROJECT_SOURCE_DIR}/fix_time_clock.patch + BUILD_COMMAND cd src && sed -i "s@^CXXFLAGS =$@CXXFLAGS = ${CXXFLAGS_NOETIC} -Wno-maybe-uninitialized@" search/Makefile && patch -p3 < ${PROJECT_SOURCE_DIR}/fix_std_vector_namespace.patch && ./build_all DOWNWARD_BITWIDTH=native && patch -p3 < ${PROJECT_SOURCE_DIR}/fix_time_clock.patch INSTALL_COMMAND bash -c "cp -rf --parents src/{validate,plan,preprocess/preprocess,search/downward*,search/unitcost,search/portfolio.py,translate} ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}" BUILD_IN_SOURCE 1 ) diff --git a/3rdparty/downward/fix_std_vector_namespace.patch b/3rdparty/downward/fix_std_vector_namespace.patch new file mode 100644 index 000000000..487dcd17b --- /dev/null +++ b/3rdparty/downward/fix_std_vector_namespace.patch @@ -0,0 +1,10 @@ +--- src/downward/src/search/landmarks/landmark_factory_zhu_givan.h.bak 2024-11-13 13:20:10.508657847 +0900 ++++ src/downward/src/search/landmarks/landmark_factory_zhu_givan.h 2024-11-13 13:20:12.591485789 +0900 +@@ -7,6 +7,7 @@ + #include "../globals.h" + + using namespace __gnu_cxx; ++using std::vector; + + class LandmarkFactoryZhuGivan : public LandmarkFactory { + private: From b349826caf7d8384640dc347d093ce7925196669 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Wed, 13 Nov 2024 15:47:03 +0900 Subject: [PATCH 31/46] [zdepth] fix build hunging issue 2nd+ time --- 3rdparty/zdepth/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/3rdparty/zdepth/CMakeLists.txt b/3rdparty/zdepth/CMakeLists.txt index 52bb0d590..ee64f419f 100644 --- a/3rdparty/zdepth/CMakeLists.txt +++ b/3rdparty/zdepth/CMakeLists.txt @@ -9,7 +9,7 @@ if("$ENV{ROS_DISTRO}" STRGREATER "kinetic") GIT_REPOSITORY https://github.com/catid/Zdepth.git GIT_TAG ac7c6d8e944d07be2404e5a1eaa04562595f3756 GIT_SHALLOW TRUE - PATCH_COMMAND cat ${PROJECT_SOURCE_DIR}/fix_cmakelists.patch | patch -p1 + PATCH_COMMAND cat ${PROJECT_SOURCE_DIR}/fix_cmakelists.patch | patch -p1 --forward || true CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} INSTALL_COMMAND echo "install" ) From dcc7c3d8b8a1cd69f2b9497a1c1e35392b67f945 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Wed, 13 Nov 2024 18:37:56 +0900 Subject: [PATCH 32/46] [sesame_ros] relax venv check --- sesame_ros/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sesame_ros/CMakeLists.txt b/sesame_ros/CMakeLists.txt index 2ff28f17e..6b7476c83 100644 --- a/sesame_ros/CMakeLists.txt +++ b/sesame_ros/CMakeLists.txt @@ -23,6 +23,7 @@ catkin_package( if($ENV{ROS_DISTRO} STRGREATER "melodic") catkin_generate_virtualenv( PYTHON_INTERPRETER python3 + CHECK_VENV FALSE ) elseif("$ENV{ROS_DISTRO}" STREQUAL "indigo") file(DOWNLOAD http://curl.haxx.se/ca/cacert.pem ${CMAKE_BINARY_DIR}/cacert.pem) @@ -34,6 +35,7 @@ elseif("$ENV{ROS_DISTRO}" STREQUAL "indigo") else() catkin_generate_virtualenv( PYTHON_INTERPRETER python2 + CHECK_VENV FALSE ) endif() From 4918f9ec67661be5c2f027586bb5098eaf9a8d55 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Sun, 17 Nov 2024 20:13:29 +0900 Subject: [PATCH 33/46] [zdepth] add comment --- 3rdparty/zdepth/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/3rdparty/zdepth/CMakeLists.txt b/3rdparty/zdepth/CMakeLists.txt index ee64f419f..b83259d48 100644 --- a/3rdparty/zdepth/CMakeLists.txt +++ b/3rdparty/zdepth/CMakeLists.txt @@ -9,7 +9,7 @@ if("$ENV{ROS_DISTRO}" STRGREATER "kinetic") GIT_REPOSITORY https://github.com/catid/Zdepth.git GIT_TAG ac7c6d8e944d07be2404e5a1eaa04562595f3756 GIT_SHALLOW TRUE - PATCH_COMMAND cat ${PROJECT_SOURCE_DIR}/fix_cmakelists.patch | patch -p1 --forward || true + PATCH_COMMAND cat ${PROJECT_SOURCE_DIR}/fix_cmakelists.patch | patch -p1 --forward || true # If there is no --forward, the build process hangs because the patch command waits interactively for input on whether a file that has already been patched can be patched again. If there is no || true , the patch command returns non-zero status if you try to use it on the patched file, then catkin build failes CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} INSTALL_COMMAND echo "install" ) From f32d0b68e2830fce1f16cb5a9127cd8e76acee00 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Sun, 17 Nov 2024 20:33:18 +0900 Subject: [PATCH 34/46] [collada_urdf_jsk_patch] ignore it because no longer needed --- jsk_3rdparty/package.xml | 2 +- jsk_ros_patch/collada_urdf_jsk_patch/CATKIN_IGNORE | 0 2 files changed, 1 insertion(+), 1 deletion(-) create mode 100644 jsk_ros_patch/collada_urdf_jsk_patch/CATKIN_IGNORE diff --git a/jsk_3rdparty/package.xml b/jsk_3rdparty/package.xml index b878b227b..ac9194395 100644 --- a/jsk_3rdparty/package.xml +++ b/jsk_3rdparty/package.xml @@ -55,7 +55,7 @@ zdepth - collada_urdf_jsk_patch + laser_filters_jsk_patch diff --git a/jsk_ros_patch/collada_urdf_jsk_patch/CATKIN_IGNORE b/jsk_ros_patch/collada_urdf_jsk_patch/CATKIN_IGNORE new file mode 100644 index 000000000..e69de29bb From 908a934a695388030aa9741bc4df4930605464a9 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Mon, 25 Nov 2024 09:57:54 +0100 Subject: [PATCH 35/46] [zdepth][sesame_ros] specify ROS_DISTRO for ros-obese --- 3rdparty/zdepth/CMakeLists.txt | 2 +- sesame_ros/CMakeLists.txt | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/3rdparty/zdepth/CMakeLists.txt b/3rdparty/zdepth/CMakeLists.txt index b83259d48..21534fb14 100644 --- a/3rdparty/zdepth/CMakeLists.txt +++ b/3rdparty/zdepth/CMakeLists.txt @@ -3,7 +3,7 @@ project(zdepth) include(ExternalProject) -if("$ENV{ROS_DISTRO}" STRGREATER "kinetic") +if(NOT "$ENV{ROS_DISTRO}" STREQUAL "indigo" OR NOT "$ENV{ROS_DISTRO}" STREQUAL "kinetic") ExternalProject_Add( zdepth GIT_REPOSITORY https://github.com/catid/Zdepth.git diff --git a/sesame_ros/CMakeLists.txt b/sesame_ros/CMakeLists.txt index 6b7476c83..f9ac9a4ae 100644 --- a/sesame_ros/CMakeLists.txt +++ b/sesame_ros/CMakeLists.txt @@ -20,9 +20,9 @@ catkin_package( CATKIN_DEPENDS message_runtime ) -if($ENV{ROS_DISTRO} STRGREATER "melodic") +if($ENV{ROS_DISTRO} STREQUAL "kinetic" OR $ENV{ROS_DISTRO} STREQUAL "melodic") catkin_generate_virtualenv( - PYTHON_INTERPRETER python3 + PYTHON_INTERPRETER python2 CHECK_VENV FALSE ) elseif("$ENV{ROS_DISTRO}" STREQUAL "indigo") @@ -34,7 +34,7 @@ elseif("$ENV{ROS_DISTRO}" STREQUAL "indigo") ) else() catkin_generate_virtualenv( - PYTHON_INTERPRETER python2 + PYTHON_INTERPRETER python3 CHECK_VENV FALSE ) endif() From 058327d55e0f63a37444e3e3f4dc77c27a8b930c Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Mon, 9 Dec 2024 11:13:20 +0900 Subject: [PATCH 36/46] fix CI, override node20 https://github.com/actions/upload-artifact/issues/616#issuecomment-2350667347 --- .github/workflows/config.yml | 21 ++++++++++++++++++++- 1 file changed, 20 insertions(+), 1 deletion(-) diff --git a/.github/workflows/config.yml b/.github/workflows/config.yml index 4abc063d1..7c1f51259 100644 --- a/.github/workflows/config.yml +++ b/.github/workflows/config.yml @@ -40,7 +40,11 @@ jobs: CATKIN_PARALLEL_JOBS: "-i" - container: ${{ matrix.CONTAINER }} + container: + image: ${{ matrix.CONTAINER }} + volumes: + - /tmp/node20:/__e/node20 + steps: - name: Install latest git ( use sudo for ros-ubuntu ) run: | @@ -63,6 +67,21 @@ jobs: git config --global --add safe.directory $GITHUB_WORKSPACE fi + - name: Try to replace `node` with an glibc 2.17 + shell: bash + run: | + if [ "${{ matrix.CONTAINER }}" = "jskrobotics/ros-ubuntu:14.04" ]; then + export USER=$(whoami) + sudo chmod 777 -R /__e/node20 + sudo chown -R $USER /__e/node20 + fi + ls -lar /__e/node20 && + sudo apt-get install -y curl && + curl -Lo /tmp/node.tar.gz https://unofficial-builds.nodejs.org/download/release/v20.17.0/node-v20.17.0-linux-x64-glibc-217.tar.gz && + cd /__e/node20 && + tar -x --strip-components=1 -f /tmp/node.tar.gz && + ls -lar /__e/node20/bin/ + - name: Checkout uses: actions/checkout@v3.0.2 From 1851db309467274f90b10c282dadda4d4245fc2e Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Wed, 25 Dec 2024 18:51:38 +0900 Subject: [PATCH 37/46] nlopt: use nlopt-2.3.tar.gz in 3rdparty/nlopt/build, instead of downloading from mit.edu --- 3rdparty/nlopt/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/3rdparty/nlopt/CMakeLists.txt b/3rdparty/nlopt/CMakeLists.txt index f9cc4f0fa..9d36d0e93 100644 --- a/3rdparty/nlopt/CMakeLists.txt +++ b/3rdparty/nlopt/CMakeLists.txt @@ -8,6 +8,8 @@ add_custom_target(libnlopt_cxx ALL DEPENDS ${CATKIN_DEVEL_PREFIX}/lib/libnlopt_cxx.so) add_custom_command(OUTPUT ${CATKIN_DEVEL_PREFIX}/lib/libnlopt_cxx.so + COMMAND mkdir -p ${CMAKE_CURRENT_BINARY_DIR}/build + COMMAND cp ${PROJECT_SOURCE_DIR}/build/nlopt-2.3.tar.gz ${CMAKE_CURRENT_BINARY_DIR}/build COMMAND cp ${PROJECT_SOURCE_DIR}/nlopt-2.3.tar.gz.md5sum ${CMAKE_CURRENT_BINARY_DIR} COMMAND mkdir -p ${CMAKE_CURRENT_BINARY_DIR}/tmp COMMAND cmake -E chdir ${CMAKE_CURRENT_BINARY_DIR} make -f ${PROJECT_SOURCE_DIR}/Makefile DSTDIR=${CMAKE_CURRENT_BINARY_DIR}/tmp MK_DIR=${mk_PREFIX}/share/mk From 98194df32d259d57819c6dba9141d0f9d862988c Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Thu, 26 Dec 2024 03:25:24 +0000 Subject: [PATCH 38/46] [respeaker_ros][diamondback] [ros-o] only use STREQUAL to compare ROS_DISTRO in cmake --- dialogflow_task_executive/CMakeLists.txt | 10 +++++----- respeaker_ros/CMakeLists.txt | 6 +++--- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/dialogflow_task_executive/CMakeLists.txt b/dialogflow_task_executive/CMakeLists.txt index f4a206208..eec641946 100644 --- a/dialogflow_task_executive/CMakeLists.txt +++ b/dialogflow_task_executive/CMakeLists.txt @@ -59,15 +59,15 @@ elseif("$ENV{ROS_DISTRO}" STREQUAL "indigo") catkin_generate_virtualenv(PYTHON_INTERPRETER python2 # https://stackoverflow.com/questions/25981703/pip-install-fails-with-connection-error-ssl-certificate-verify-failed EXTRA_PIP_ARGS -vvv --cert=${CMAKE_BINARY_DIR}/cacert.pem) -elseif("$ENV{ROS_DISTRO}" STRGREATER "melodic") +elseif("$ENV{ROS_DISTRO}" STREQUAL "kinetic" OR "$ENV{ROS_DISTRO}" STREQUAL "melodic") catkin_generate_virtualenv( - INPUT_REQUIREMENTS requirements.in.noetic - PYTHON_INTERPRETER python3 + INPUT_REQUIREMENTS requirements.in + PYTHON_INTERPRETER python2 ) else() catkin_generate_virtualenv( - INPUT_REQUIREMENTS requirements.in - PYTHON_INTERPRETER python2 + INPUT_REQUIREMENTS requirements.in.noetic + PYTHON_INTERPRETER python3 ) endif() diff --git a/respeaker_ros/CMakeLists.txt b/respeaker_ros/CMakeLists.txt index d6752f005..0eb66f1df 100644 --- a/respeaker_ros/CMakeLists.txt +++ b/respeaker_ros/CMakeLists.txt @@ -14,9 +14,9 @@ generate_dynamic_reconfigure_options( catkin_package() -if($ENV{ROS_DISTRO} STRGREATER "melodic") +if("$ENV{ROS_DISTRO}" STREQUAL "kinetic" OR "$ENV{ROS_DISTRO}" STREQUAL "melodic") catkin_generate_virtualenv( - PYTHON_INTERPRETER python3 + PYTHON_INTERPRETER python2 CHECK_VENV FALSE ) elseif("$ENV{ROS_DISTRO}" STREQUAL "indigo") @@ -28,7 +28,7 @@ elseif("$ENV{ROS_DISTRO}" STREQUAL "indigo") ) else() catkin_generate_virtualenv( - PYTHON_INTERPRETER python2 + PYTHON_INTERPRETER python3 CHECK_VENV FALSE ) endif() From c8eb21e211d1a8f803cd55549a5b2bdc87e6ff9f Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Thu, 26 Dec 2024 03:27:16 +0000 Subject: [PATCH 39/46] [libsiftfast] [ros-o] only use != to compare ROS_DISTRO in Makefile --- 3rdparty/libsiftfast/Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/3rdparty/libsiftfast/Makefile b/3rdparty/libsiftfast/Makefile index b330cb1c7..70c618026 100644 --- a/3rdparty/libsiftfast/Makefile +++ b/3rdparty/libsiftfast/Makefile @@ -24,7 +24,7 @@ clone: $(SVN_DIR) patch: clone cd $(SVN_DIR) && svn revert --recursive . && for patch in $(SOURCE_DIR)/patches/0*.patch; do patch -p0 -f -E < $$patch; done # for python3 - if [ "${ROS_DISTRO}" \> "melodic" ]; then cd $(SVN_DIR) && svn revert --recursive . && for patch in $(SOURCE_DIR)/patches/1*.patch; do patch -p0 -f -E < $$patch; done; fi + if [ "${ROS_DISTRO}" != "kinetic" -a "${ROS_DISTRO}" != "melodic" ]; then cd $(SVN_DIR) && svn revert --recursive . && for patch in $(SOURCE_DIR)/patches/1*.patch; do patch -p0 -f -E < $$patch; done; fi libsiftfast: patch cd $(SVN_DIR)/$(BUILDDIR) && BOOST_INCLUDEDIR=$(BOOST_INCLUDE_DIRS) BOOST_LIBRARYDIR=$(BOOST_LIBRARY_DIRS) cmake -DCMAKE_INSTALL_PREFIX=$(INSTALL_DIR) -DCMAKE_BUILD_TYPE=$(CMAKE_BUILD_TYPE) .. && make $(ROS_PARALLEL_JOBS) install From 63b2c78d96888ef9b1c1ef629a361008e52d766a Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Thu, 26 Dec 2024 03:27:40 +0000 Subject: [PATCH 40/46] [downward] [ros-o] add -Wno-maybe-uninitialized --- 3rdparty/downward/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/3rdparty/downward/CMakeLists.txt b/3rdparty/downward/CMakeLists.txt index ae19b0264..e270fdb1b 100644 --- a/3rdparty/downward/CMakeLists.txt +++ b/3rdparty/downward/CMakeLists.txt @@ -14,7 +14,7 @@ externalproject_add(downward URL http://cdn.rawgit.com/jsk-ros-pkg/archives/master/Fast-Downward-f33d3b65601f.tar.gz TIMEOUT 120 CONFIGURE_COMMAND "" - BUILD_COMMAND cd src && sed -i "s@^CXXFLAGS =$@CXXFLAGS = ${CXXFLAGS_NOETIC} -Wno-maybe-uninitialized@" search/Makefile && patch -p3 < ${PROJECT_SOURCE_DIR}/fix_std_vector_namespace.patch && ./build_all DOWNWARD_BITWIDTH=native && patch -p3 < ${PROJECT_SOURCE_DIR}/fix_time_clock.patch + BUILD_COMMAND cd src && sed -i "s@^CXXFLAGS =$@CXXFLAGS = ${CXXFLAGS_NOETIC} -Wno-deprecated-copy -Wno-maybe-uninitialized@" search/Makefile && patch -p3 < ${PROJECT_SOURCE_DIR}/fix_std_vector_namespace.patch && ./build_all DOWNWARD_BITWIDTH=native && patch -p3 < ${PROJECT_SOURCE_DIR}/fix_time_clock.patch INSTALL_COMMAND bash -c "cp -rf --parents src/{validate,plan,preprocess/preprocess,search/downward*,search/unitcost,search/portfolio.py,translate} ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}" BUILD_IN_SOURCE 1 ) From 3f42be359266a780ca2fe853a46dc2a21b49bd84 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Thu, 26 Dec 2024 03:57:56 +0000 Subject: [PATCH 41/46] [zdepth] [ros-o] only use STREQUAL to compare ROS_DISTRO in cmake --- 3rdparty/zdepth/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/3rdparty/zdepth/CMakeLists.txt b/3rdparty/zdepth/CMakeLists.txt index 21534fb14..08b996951 100644 --- a/3rdparty/zdepth/CMakeLists.txt +++ b/3rdparty/zdepth/CMakeLists.txt @@ -3,7 +3,9 @@ project(zdepth) include(ExternalProject) -if(NOT "$ENV{ROS_DISTRO}" STREQUAL "indigo" OR NOT "$ENV{ROS_DISTRO}" STREQUAL "kinetic") +if(("$ENV{ROS_DISTRO}" STREQUAL "indigo") OR ("$ENV{ROS_DISTRO}" STREQUAL "kinetic")) + install(CODE "message(WARNING \"Skipping zdepth install because ROS is too old\")") +else() ExternalProject_Add( zdepth GIT_REPOSITORY https://github.com/catid/Zdepth.git @@ -15,6 +17,4 @@ if(NOT "$ENV{ROS_DISTRO}" STREQUAL "indigo" OR NOT "$ENV{ROS_DISTRO}" STREQUAL " ) install(CODE "execute_process(COMMAND make install WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/zdepth-prefix/src/zdepth-build)") -else() - install(CODE "message(WARNING \"Skipping zdepth install because ROS is too old\")") endif() From 8f15e3544229274f3d3190f1b6419a83b99fe0f8 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Thu, 26 Dec 2024 03:58:31 +0000 Subject: [PATCH 42/46] [collada_urdf_jsk_patch] [ros-o] add CATKIN_IGNORE only when ROS-O, use STREQUAL to compare ROS_DISTRO in cmake --- jsk_ros_patch/collada_urdf_jsk_patch/CATKIN_IGNORE | 0 jsk_ros_patch/collada_urdf_jsk_patch/CMakeLists.txt | 11 +++++++++-- 2 files changed, 9 insertions(+), 2 deletions(-) delete mode 100644 jsk_ros_patch/collada_urdf_jsk_patch/CATKIN_IGNORE diff --git a/jsk_ros_patch/collada_urdf_jsk_patch/CATKIN_IGNORE b/jsk_ros_patch/collada_urdf_jsk_patch/CATKIN_IGNORE deleted file mode 100644 index e69de29bb..000000000 diff --git a/jsk_ros_patch/collada_urdf_jsk_patch/CMakeLists.txt b/jsk_ros_patch/collada_urdf_jsk_patch/CMakeLists.txt index 322560351..65643bfb6 100644 --- a/jsk_ros_patch/collada_urdf_jsk_patch/CMakeLists.txt +++ b/jsk_ros_patch/collada_urdf_jsk_patch/CMakeLists.txt @@ -5,12 +5,19 @@ project(collada_urdf_jsk_patch) if(("$ENV{ROS_DISTRO}" STREQUAL "groovy") OR ("$ENV{ROS_DISTRO}" STREQUAL "hydro")) set(SOURCE_DISTRO hydro-devel) set(GIT_REPO robot_model) -elseif ("$ENV{ROS_DISTRO}" STRLESS "melodic") +elseif (("$ENV{ROS_DISTRO}" STREQUAL "indigo") OR ("$ENV{ROS_DISTRO}" STREQUAL "jade") OR ("$ENV{ROS_DISTRO}" STREQUAL "kinetic")) set(SOURCE_DISTRO bd4fc369d56eaa0c31d8cb17677e00b9d9685de6) # 1.11.13, before strip indigo set(GIT_REPO robot_model) -elseif ("$ENV{ROS_DISTRO}" STREQUAL "melodic" OR "$ENV{ROS_DISTRO}" STRGREATER "melodic") +elseif (("$ENV{ROS_DISTRO}" STREQUAL "melodic") OR ("$ENV{ROS_DISTRO}" STREQUAL "noetic")) set(SOURCE_DISTRO 923c5d33bd245e82134e8ae02e4c9d379e80eb27) # 1.12.12 set(GIT_REPO collada_urdf) +else() + find_package(catkin REQUIRED) + catkin_package(CATKIN_DEPENDS) + file(TOUCH ${CMAKE_CURRENT_BINARY_DIR}/CATKIN_IGNORE) + install(FILES ${CMAKE_CURRENT_BINARY_DIR}/CATKIN_IGNORE #catkin_lint: ignore_once missing_file + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + return() endif() if ("$ENV{ROS_DISTRO}" STREQUAL "kinetic" OR "$ENV{ROS_DISTRO}" STRGREATER "kinetic") set(CXXFLAGS CXXFLAGS=-std=gnu++11) From 0960beae65d5b55f67c69309dce306401c8f0a72 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Thu, 26 Dec 2024 06:29:12 +0000 Subject: [PATCH 43/46] [.github/workflows/config.yml] add ROS-O test --- .github/workflows/config.yml | 59 ++++++++++++++++++++++++++++++++++++ 1 file changed, 59 insertions(+) diff --git a/.github/workflows/config.yml b/.github/workflows/config.yml index 7c1f51259..91c6a98e2 100644 --- a/.github/workflows/config.yml +++ b/.github/workflows/config.yml @@ -204,3 +204,62 @@ jobs: if: always() run: | rm -fr ${{ matrix.ROS_DISTRO }}-${{ github.run_number }}-${{ github.run_attempt }}-${{ github.run_id }} || echo "OK" + +# ROS-O setup https://github.com/v4hn/ros-o-builder/blob/jammy-one/README.md#install-instructions + ros-o: + runs-on: ubuntu-latest + + strategy: + fail-fast: false + matrix: + include: + - DISTRO: ubuntu:22.04 + ROS_REPOSITORY_URL: https://raw.githubusercontent.com/v4hn/ros-o-builder/jammy-one/repository + + container: ${{ matrix.DISTRO }} + + env: + DEBIAN_FRONTEND : noninteractive + + steps: + - name: Chcekout Source + uses: actions/checkout@v3.0.2 + + - name: Setup ROS-O deb repository + run: | + set -x + apt update && apt install -qq -y ca-certificates + echo "deb [trusted=yes] ${{ matrix.ROS_REPOSITORY_URL }}/ ./" | tee /etc/apt/sources.list.d/ros-o-builder.list + apt update + apt install -qq -y python3-rosdep2 + echo "yaml ${{ matrix.ROS_REPOSITORY_URL }}/local.yaml debian" | tee /etc/ros/rosdep/sources.list.d/1-ros-o-builder.list + rosdep update + + - name: Setup catkin-tools + run: | + set -x + # setup catkin tools + apt install -qq -y python3-pip + pip3 install catkin-tools + # setup build tools + apt install -qq -y cmake build-essential catkin ros-one-rosbash + + - name: Setup Workspace + run: | + source /opt/ros/one/setup.bash + set -x + # setup workspace + mkdir -p ~/ws/src + cd ~/ws/src + ln -sf $GITHUB_WORKSPACE . + rosdep install -qq -r -y --from-path . --ignore-src || echo "OK" + shell: bash + + - name: Compile Packages + run: | + source /opt/ros/one/setup.bash + set -x + cd ~/ws/ + catkin build --no-status -sv ${{ matrix.CATKIN_OPTIONS }} --cmake-args -DCATKIN_ENABLE_TESTING=OFF -DCMAKE_VERBOSE_MAKEFILE:BOOL=ON ${{ matrix.CMAKE_OPTIONS }} + shell: bash + From 90648163a093a4bf511d2dd03d431cc106fa5022 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Mon, 30 Dec 2024 00:50:07 +0000 Subject: [PATCH 44/46] [.github/workflows/config.yml: disable installing recommends as ros-o-builder do --- .github/workflows/config.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/config.yml b/.github/workflows/config.yml index 91c6a98e2..b4cdb25fa 100644 --- a/.github/workflows/config.yml +++ b/.github/workflows/config.yml @@ -234,6 +234,8 @@ jobs: apt install -qq -y python3-rosdep2 echo "yaml ${{ matrix.ROS_REPOSITORY_URL }}/local.yaml debian" | tee /etc/ros/rosdep/sources.list.d/1-ros-o-builder.list rosdep update + # disable installing recommends as ros-o-builder do + echo 'APT::Install-Recommends "false";' | tee /etc/apt/apt.conf.d/99norecommends - name: Setup catkin-tools run: | From 7c8a968622ec0d015a77a25920729ad4a91bbcb3 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Mon, 30 Dec 2024 03:26:11 +0000 Subject: [PATCH 45/46] [3rdparty/downward/package.xml: add linbfl-dev for FlexLexer.h --- 3rdparty/downward/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/3rdparty/downward/package.xml b/3rdparty/downward/package.xml index aa752c913..c6fa3ac05 100644 --- a/3rdparty/downward/package.xml +++ b/3rdparty/downward/package.xml @@ -17,6 +17,7 @@ python python3 flex + libfl-dev bison gawk rostest From ed63e706eaf65d6b2804ef3d456c5173af0d7fab Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Mon, 30 Dec 2024 08:29:27 +0000 Subject: [PATCH 46/46] [nfc_ros] nfcpy requries python3.6+, skip kinetic which has python3.5 --- nfc_ros/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nfc_ros/CMakeLists.txt b/nfc_ros/CMakeLists.txt index 98e3d1c62..488994054 100644 --- a/nfc_ros/CMakeLists.txt +++ b/nfc_ros/CMakeLists.txt @@ -20,7 +20,7 @@ catkin_package( CATKIN_DEPENDS message_runtime ) -if ("$ENV{ROS_DISTRO}" MATCHES "indigo") +if ("$ENV{ROS_DISTRO}" MATCHES "indigo" OR "$ENV{ROS_DISTRO}" MATCHES "kinetic") message(WARNING "nfc_ros requires python3.6 or newer. For indigo, virtualenv generation is skipped.") else() catkin_generate_virtualenv( @@ -36,7 +36,7 @@ install(FILES requirements.txt DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) -if(CATKIN_ENABLE_TESTING) +if(CATKIN_ENABLE_TESTING AND ("$ENV{ROS_DISTRO}" MATCHES "indigo" OR "$ENV{ROS_DISTRO}" MATCHES "kinetic")) find_package(rostest REQUIRED) add_rostest(test/test_rospy_node.test DEPENDENCIES ${PROJECT_NAME}_generate_virtualenv