From 9f3749e1c51d0a956d6ed4ad69b1087ce7d27a4a Mon Sep 17 00:00:00 2001 From: Sergi Hernandez Juan <shernand@iri.upc.edu> Date: Wed, 22 Sep 2021 12:12:10 +0200 Subject: [PATCH] Initial commit --- CMakeLists.txt | 10 ++-- README.md | 117 +++++++++++-------------------------- cfg/Node.cfg | 4 +- docs/README.md | 66 --------------------- docs/python_virtual_env.md | 31 ---------- launch/node.launch | 4 +- launch/test.launch | 6 +- package.xml | 6 +- src/node.py | 12 ++-- 9 files changed, 56 insertions(+), 200 deletions(-) delete mode 100644 docs/README.md delete mode 100644 docs/python_virtual_env.md diff --git a/CMakeLists.txt b/CMakeLists.txt index 1c35665..1cde27c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.0.2) -project(iri_python_template) +project(iri_gesture_recognition) ## Compile as C++11, supported in ROS Kinetic and newer # add_compile_options(-std=c++11) @@ -107,7 +107,7 @@ generate_dynamic_reconfigure_options( ## DEPENDS: system dependencies of this project that dependent projects also need catkin_package( # INCLUDE_DIRS include -# LIBRARIES iri_python_template +# LIBRARIES iri_gesture_recognition CATKIN_DEPENDS rospy std_msgs std_srvs dynamic_reconfigure # DEPENDS system_lib ) @@ -125,7 +125,7 @@ include_directories( ## Declare a C++ library # add_library(${PROJECT_NAME} -# src/${PROJECT_NAME}/iri_python_template.cpp +# src/${PROJECT_NAME}/iri_gesture_recognition.cpp # ) ## Add cmake target dependencies of the library @@ -136,7 +136,7 @@ include_directories( ## Declare a C++ executable ## With catkin_make all packages are built within a single CMake context ## The recommended prefix ensures that target names across packages don't collide -# add_executable(${PROJECT_NAME}_node src/iri_python_template_node.cpp) +# add_executable(${PROJECT_NAME}_node src/iri_gesture_recognition_node.cpp) ## Rename C++ executable without prefix ## The above recommended prefix causes long target names, the following renames the @@ -200,7 +200,7 @@ include_directories( ############# ## Add gtest based cpp test target and link libraries -# catkin_add_gtest(${PROJECT_NAME}-test test/test_iri_python_template.cpp) +# catkin_add_gtest(${PROJECT_NAME}-test test/test_iri_gesture_recognition.cpp) # if(TARGET ${PROJECT_NAME}-test) # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) # endif() diff --git a/README.md b/README.md index 274faef..3914536 100644 --- a/README.md +++ b/README.md @@ -1,113 +1,66 @@ -# Description +## Description -This repository contains a ROS Python template that can be used to integrate user Python libraries and code into ROS in an easy way. It provides examples of creation and use of: +# ROS Interface -* Topic publishers -* Topic subscribers -* Service server -* Service client -* Dynamic reconfigure +### Topic publishers -The main features of this template node are: + - **topic name** (message type): description. -* Has a independent thread to execute the user code (*main_thread*). -* Has a dynamic reconfigure server -* Has a configurable rate for the *main_thread* (*rate*) +### Topic subscribers -# How to use it + - **topic name** (message type): description. -The steps to use this template are described next. +### Service servers -## Create a new ROS package from the template + - **service name** (message type): description. -To create a new ROS package from the template, first clone the template repository into the working workspace: +### Service clients -``` -roscd -cd ../src -git clone ssh://git@gitlab.iri.upc.edu:2202/labrobotica/ros/iri_core/iri_python_template.git <my_package_name> -``` + - **service name** (message type): description. -where <my_package_name> is the desired name for the new package. +### Parameters -Change the default name of all internal classes and variables to the desired package and class names: +- ~**param name** (type; default: value; min: value; max: value) Description. -``` -my_package_name=<my_package_name> -my_node_class_name=<my_node_class_name> - -cd $my_package_name -sed -i "s/iri_python_template/$my_package_name/g" CMakeLists.txt -sed -i "s/iri_python_template/$my_package_name/g" package.xml -sed -i "s/iri_python_template/$my_package_name/g" src/node.py -sed -i "s/iri_python_template/$my_package_name/g" cfg/Node.cfg -sed -i "s/iri_python_template/$my_package_name/g" launch/node.launch -sed -i "s/iri_python_template/$my_package_name/g" launch/test.launch -sed -i "s/template_Node/$my_node_class_name/g" src/node.py -``` +## Dependencies +This package requires the following packages: -Substitute the template documentation for a genric one: +## Installation -``` -cp docs/README.md README.md -rm -rf docs +Move to the active workspace: +```bash +roscd && cd ../src ``` -Create a new repository in the [IRI GitLab server](https://gitlab.iri.upc.edu/). Once created, execute the following command to change the remote repository and push the files: - -``` -git remote rename origin old-origin -git remote add origin <path to the new repository> -git push -u origin --all +Clone the repository: +```bash +git clone <url> ``` -## Add ROS interfaces - -The Python node by default has an example of creating and using: - -* topic publisher (*publisher_example*) -* topic subscriber (*subscriber_example*) -* service server (*service_server_example*) -* service client (*service_client_example*) - -You can use this examples to add necessary ROS interfaces to your node. Remember to remove or comment the example ROS interfaces. - -For each new topic or service, it is also necessary to import their definitions. To do so, at the beginning of the python file (under the *Add any ROS dependency tag*), add one of the following lines for each of the new topics or services: - +Install ROS dependencies: ``` -from <package_name>.<folder> import <topic or service name> +roscd +cd .. +rosdep install -i -r --from-paths src ``` -## Add ROS parameters - -The python ROS node supports the dynamic reconfigure feature of ROS. To use it: - -* Add the necessary parameters to the cfg/Node.cfg file following the same syntax as the examples provided. Remember to remove or comment the example parameters. -* Add the necessary handling code in the *dyn_reconf_callback* function. - -Parameters can also be provided outside of the dynamic reconfigure framework. In this case, use the following command to get the actual value of the parameters when needed: - +Compile the workspace: ``` -self.<param_variable> = rospy.get_param('~<param_name>', '<param_default_value>') +catkin_make ``` -## Basic operation +## Launch -This package is intended to be used in a Python virtual environment to avoid any possible conflict with some Python libraries already installed in the system. To create a Python virtual environment, follow the instructions in [here](docs/python_virtual_env.md). +Description of the launch files. -To launch the Python node into a desired virtual environment, execute the following command: +## Disclaimer -``` -roslaunch <package_name> test.launch virtual_env_path:=`rospack find <package_name>`/<virtual environment path> -``` +Copyright (C) Institut de Robòtica i Informà tica Industrial, CSIC-UPC. +Mantainer IRI labrobotics (labrobotica@iri.upc.edu) -It is possible to disable the use of the virtual environment by providing an invalid path in the launch file or commenting the following lines in the *node.py* file, although it is highly discouraged: +This package is distributed in the hope that it will be useful, but without any warranty. It is provided "as is" without warranty of any kind, either expressed or implied, including, but not limited to, the implied warranties of merchantability and fitness for a particular purpose. The entire risk as to the quality and performance of the program is with you. should the program prove defective, the GMR group does not assume the cost of any necessary servicing, repair or correction. -``` -from venv_utils import activate_virtual_env -venv_status = activate_virtual_env() -``` +In no event unless required by applicable law the author will be liable to you for damages, including any general, special, incidental or consequential damages arising out of the use or inability to use the program (including but not limited to loss of data or data being rendered inaccurate or losses sustained by you or third parties or a failure of the program to operate with any other programs), even if the author has been advised of the possibility of such damages. -Once started, all the topic and service callbacks, as well as the *main_thread* function, are executed in parallel. The *main_thread* function is intended to be used as the main loop function where most of the user code is executed. +You should have received a copy of the GNU Lesser General Public License along with this program. If not, see <http://www.gnu.org/licenses/> -The topic and service callbacks can also include user code as necessary. diff --git a/cfg/Node.cfg b/cfg/Node.cfg index 3751a3b..8bc523c 100755 --- a/cfg/Node.cfg +++ b/cfg/Node.cfg @@ -1,5 +1,5 @@ #!/usr/bin/env python -PACKAGE = "iri_python_template" +PACKAGE = "iri_gesture_recognition" from dynamic_reconfigure.parameter_generator_catkin import * @@ -19,4 +19,4 @@ size_enum = gen.enum([ gen.const("Small", int_t, 0, "A small constant"), gen.add("size", int_t, 0, "A size parameter which is edited via an enum", 1, 0, 3, edit_method=size_enum) -exit(gen.generate(PACKAGE, "iri_python_template", "Node")) +exit(gen.generate(PACKAGE, "iri_gesture_recognition", "Node")) diff --git a/docs/README.md b/docs/README.md deleted file mode 100644 index 3914536..0000000 --- a/docs/README.md +++ /dev/null @@ -1,66 +0,0 @@ -## Description - -# ROS Interface - -### Topic publishers - - - **topic name** (message type): description. - -### Topic subscribers - - - **topic name** (message type): description. - -### Service servers - - - **service name** (message type): description. - -### Service clients - - - **service name** (message type): description. - -### Parameters - -- ~**param name** (type; default: value; min: value; max: value) Description. - -## Dependencies -This package requires the following packages: - -## Installation - -Move to the active workspace: -```bash -roscd && cd ../src -``` - -Clone the repository: -```bash -git clone <url> -``` - -Install ROS dependencies: -``` -roscd -cd .. -rosdep install -i -r --from-paths src -``` - -Compile the workspace: -``` -catkin_make -``` - -## Launch - -Description of the launch files. - -## Disclaimer - -Copyright (C) Institut de Robòtica i Informà tica Industrial, CSIC-UPC. -Mantainer IRI labrobotics (labrobotica@iri.upc.edu) - -This package is distributed in the hope that it will be useful, but without any warranty. It is provided "as is" without warranty of any kind, either expressed or implied, including, but not limited to, the implied warranties of merchantability and fitness for a particular purpose. The entire risk as to the quality and performance of the program is with you. should the program prove defective, the GMR group does not assume the cost of any necessary servicing, repair or correction. - -In no event unless required by applicable law the author will be liable to you for damages, including any general, special, incidental or consequential damages arising out of the use or inability to use the program (including but not limited to loss of data or data being rendered inaccurate or losses sustained by you or third parties or a failure of the program to operate with any other programs), even if the author has been advised of the possibility of such damages. - -You should have received a copy of the GNU Lesser General Public License along with this program. If not, see <http://www.gnu.org/licenses/> - diff --git a/docs/python_virtual_env.md b/docs/python_virtual_env.md deleted file mode 100644 index cfca28f..0000000 --- a/docs/python_virtual_env.md +++ /dev/null @@ -1,31 +0,0 @@ -# Create a Python virtual environment - -To install and setup the python virtual environment, follow the next steps: - -* Install the pip application, if not already installed, and update it: -``` -sudo apt install python-pip -pip install -U pip -``` -* Install the virtual environment library. We use the simple virtualenv tool instead of anaconda because of ROS compatibility issues. -``` -pip install virtualenv -``` -* Move to the desired folder where the virtual environment will be located: -``` -cd <virtual environment path> -``` -* Create the virtual environment: -``` -virtualenv <virtual_environment_name> -``` -* To activate the virtual environment: -``` -source <virtual_environment_name>/bin/activate -``` -* Install all the dependencies with pip install. - -* To deactivate the virtual environment -``` -deactivate -``` diff --git a/launch/node.launch b/launch/node.launch index 0a6375d..1c714fe 100644 --- a/launch/node.launch +++ b/launch/node.launch @@ -7,12 +7,12 @@ <arg name="subscriber_topic_name" default="~subscriber_topic_name"/> <arg name="service_server_name" default="~service_server_name"/> <arg name="service_client_name" default="~service_client_name"/> - <arg name="param_file" default="$(find iri_python_template)/config/params.yaml"/> + <arg name="param_file" default="$(find iri_gesture_recognition)/config/params.yaml"/> <arg name="virtual_env_path" default="$(env HOME)/virtual_env"/> <arg name="output" default="screen"/> - <node pkg="iri_python_template" + <node pkg="iri_gesture_recognition" name="$(arg node_name)" type="node.py" output="$(arg output)" diff --git a/launch/test.launch b/launch/test.launch index 18af0e2..70651fd 100644 --- a/launch/test.launch +++ b/launch/test.launch @@ -3,16 +3,16 @@ <launch> <arg name="output" default="screen"/> - <arg name="virtual_env_path" default="$(find iri_python_template)/virtual_etual_env"/> + <arg name="virtual_env_path" default="$(find iri_gesture_recognition)/virtual_etual_env"/> - <include file="$(find iri_python_template)/launch/node.launch"> + <include file="$(find iri_gesture_recognition)/launch/node.launch"> <arg name="node_name" value="test_node"/> <arg name="output" value="$(arg output)"/> <arg name="publisher_topic_name" value="/test_node/pub"/> <arg name="subscriber_topic_name" value="/test_node/sub"/> <arg name="service_server_name" value="/test_node/service"/> <arg name="service_client_name" value="/test_node/service"/> - <arg name="param_file" value="$(find iri_python_template)/config/params.yaml"/> + <arg name="param_file" value="$(find iri_gesture_recognition)/config/params.yaml"/> <arg name="virtual_env_path" value="$(arg virtual_env_path)"/> </include> diff --git a/package.xml b/package.xml index 042cbc8..51fc8ce 100644 --- a/package.xml +++ b/package.xml @@ -1,8 +1,8 @@ <?xml version="1.0"?> <package format="2"> - <name>iri_python_template</name> + <name>iri_gesture_recognition</name> <version>1.0.0</version> - <description>The iri_python_template package</description> + <description>The iri_gesture_recognition package</description> <!-- One maintainer tag required, multiple allowed, one person per tag --> <!-- Example: --> @@ -19,7 +19,7 @@ <!-- Url tags are optional, but multiple are allowed, one per tag --> <!-- Optional attribute type can be: website, bugtracker, or repository --> <!-- Example: --> - <!-- <url type="website">http://wiki.ros.org/iri_python_template</url> --> + <!-- <url type="website">http://wiki.ros.org/iri_gesture_recognition</url> --> <!-- Author tags are optional, multiple are allowed, one per tag --> diff --git a/src/node.py b/src/node.py index 5afcb99..65b8cbb 100755 --- a/src/node.py +++ b/src/node.py @@ -12,7 +12,7 @@ venv_status = activate_virtual_env() import sys from threading import Thread -from iri_python_template.cfg import NodeConfig as Config +from iri_gesture_recognition.cfg import NodeConfig as Config ######################################### # Add any ROS dependency @@ -49,7 +49,7 @@ def main_thread(arg): ######################################### arg.rate.sleep() -class template_Node: +class GestureRecognitionNode: def __init__(self): # get the main thread desired rate of the node @@ -65,7 +65,7 @@ class template_Node: # Initialize action clients and servers # Initialize user libraries and variables ######################################### - rospy.loginfo(rospy.get_caller_id() + ": Init template_Node") + rospy.loginfo(rospy.get_caller_id() + ": Init GestureRecognitionNode") # Create topic publisher (String.msg) self.publisher_example = rospy.Publisher("~publisher_topic_name", String, queue_size=1) @@ -79,7 +79,7 @@ class template_Node: self.custom_param = rospy.get_param('~custom_param', 'default value') rospy.loginfo(rospy.get_caller_id() + ": Got parameter custom_param= %s", self.custom_param) - rospy.loginfo(rospy.get_caller_id() + ": Init template_Node Done") + rospy.loginfo(rospy.get_caller_id() + ": Init GestureRecognitionNode Done") ######################################### # USER CODE ENDS HERE ######################################### @@ -123,8 +123,8 @@ class template_Node: def main(args): - rospy.init_node('iri_python_template', anonymous=False) - tn = template_Node() + rospy.init_node('iri_gesture_recognition', anonymous=False) + tn = GestureRecognitionNode() rospy.spin() if __name__ == '__main__': -- GitLab