Skip to content
Snippets Groups Projects
Verified Commit e902ea68 authored by Anton Tetov Johansson's avatar Anton Tetov Johansson
Browse files

remove catkin_virtualenv to fix build

parent 66301060
Branches
No related tags found
No related merge requests found
cmake_minimum_required(VERSION 3.0.2) cmake_minimum_required(VERSION 3.0.2)
project(ros_jr3_comedi) project(ros_jr3_comedi)
find_package(catkin REQUIRED catkin_virtualenv) find_package(catkin REQUIRED )
catkin_generate_virtualenv(
INPUT_REQUIREMENTS requirements.in
USE_SYSTEM_PACKAGES TRUE
)
catkin_install_python( catkin_install_python(
PROGRAMS PROGRAMS
nodes/publisher nodes/publisher
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
) )
install(FILES
requirements.txt
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
# # ros_jr3_comedi
## Build ## Build
...@@ -7,8 +7,13 @@ source /usr/lib64/ros/setup.bash ...@@ -7,8 +7,13 @@ source /usr/lib64/ros/setup.bash
source ~/catkin_ws/devel_isolated/setup.bash source ~/catkin_ws/devel_isolated/setup.bash
mkdir -p ~/catkin_ws/src 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 git clone https://gitlab.control.lth.se/tetov/ros_jr3_comedi.git
cd .. cd ..
...@@ -20,6 +25,7 @@ catkin_make_isolated ...@@ -20,6 +25,7 @@ catkin_make_isolated
```bash ```bash
source /usr/lib64/ros/setup.bash source /usr/lib64/ros/setup.bash
source ~/catkin_ws/devel_isolated/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 export ROS_MASTER_URI=http://130.235.83.121:11311
roslaunch ros_jr3_comedi publish.launch roslaunch ros_jr3_comedi publish.launch
......
#!/usr/bin/env python
import rospy import rospy
from geometry_msgs.msg import Vector3, Wrench, WrenchStamped from geometry_msgs.msg import Vector3, Wrench, WrenchStamped
......
...@@ -13,7 +13,6 @@ ...@@ -13,7 +13,6 @@
<build_depend>rospy</build_depend> <build_depend>rospy</build_depend>
<build_depend>geometry_msg</build_depend> <build_depend>geometry_msg</build_depend>
<build_depend>std_msgs</build_depend> <build_depend>std_msgs</build_depend>
<build_depend>catkin_virtualenv</build_depend>
<build_export_depend>roscpp</build_export_depend> <build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend> <build_export_depend>rospy</build_export_depend>
...@@ -25,8 +24,6 @@ ...@@ -25,8 +24,6 @@
<exec_depend>geometry_msg</exec_depend> <exec_depend>geometry_msg</exec_depend>
<exec_depend>std_msgs</exec_depend> <exec_depend>std_msgs</exec_depend>
<depend>pexpect</depend>
<export> <export>
<pip_requirements>requirements.txt</pip_requirements> <pip_requirements>requirements.txt</pip_requirements>
</export> </export>
......
pexpect >= 4.8.0
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment