From e902ea684d48a86a2a3d1e57440317ff9a29d23b Mon Sep 17 00:00:00 2001 From: Anton Tetov <anton@tetov.se> Date: Fri, 15 Oct 2021 16:30:36 +0200 Subject: [PATCH] remove catkin_virtualenv to fix build --- CMakeLists.txt | 12 +----------- README.md | 10 ++++++++-- nodes/publisher | 2 ++ package.xml | 3 --- requirements.in | 1 - 5 files changed, 11 insertions(+), 17 deletions(-) mode change 100644 => 100755 nodes/publisher delete mode 100644 requirements.in diff --git a/CMakeLists.txt b/CMakeLists.txt index 9f50750..f5e4d36 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,20 +1,10 @@ cmake_minimum_required(VERSION 3.0.2) project(ros_jr3_comedi) -find_package(catkin REQUIRED catkin_virtualenv) - -catkin_generate_virtualenv( - INPUT_REQUIREMENTS requirements.in - USE_SYSTEM_PACKAGES TRUE -) +find_package(catkin REQUIRED ) catkin_install_python( PROGRAMS nodes/publisher DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) - -install(FILES - requirements.txt - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) diff --git a/README.md b/README.md index de221bd..2ef21c1 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ -# +# ros_jr3_comedi ## Build @@ -7,8 +7,13 @@ source /usr/lib64/ros/setup.bash source ~/catkin_ws/devel_isolated/setup.bash mkdir -p ~/catkin_ws/src +cd ~/catkin_ws/ -cd ~/catkin_ws/src +virtualenv venv +source venv/bin/activate +pip install pexpect >= 4.8.0 + +cd src git clone https://gitlab.control.lth.se/tetov/ros_jr3_comedi.git cd .. @@ -20,6 +25,7 @@ catkin_make_isolated ```bash source /usr/lib64/ros/setup.bash source ~/catkin_ws/devel_isolated/setup.bash +source ~/catkin_ws/venv/bin/activate export ROS_MASTER_URI=http://130.235.83.121:11311 roslaunch ros_jr3_comedi publish.launch diff --git a/nodes/publisher b/nodes/publisher old mode 100644 new mode 100755 index 2b9a438..16ef472 --- a/nodes/publisher +++ b/nodes/publisher @@ -1,3 +1,5 @@ +#!/usr/bin/env python + import rospy from geometry_msgs.msg import Vector3, Wrench, WrenchStamped diff --git a/package.xml b/package.xml index 9eeb6b5..edfc556 100644 --- a/package.xml +++ b/package.xml @@ -13,7 +13,6 @@ <build_depend>rospy</build_depend> <build_depend>geometry_msg</build_depend> <build_depend>std_msgs</build_depend> - <build_depend>catkin_virtualenv</build_depend> <build_export_depend>roscpp</build_export_depend> <build_export_depend>rospy</build_export_depend> @@ -25,8 +24,6 @@ <exec_depend>geometry_msg</exec_depend> <exec_depend>std_msgs</exec_depend> - <depend>pexpect</depend> - <export> <pip_requirements>requirements.txt</pip_requirements> </export> diff --git a/requirements.in b/requirements.in deleted file mode 100644 index dcf2886..0000000 --- a/requirements.in +++ /dev/null @@ -1 +0,0 @@ -pexpect >= 4.8.0 -- GitLab