Package to control a 3F gripper Gripper from Robotiq inc.
Jean-Philippe RobergeBSDhttp://ros.org/wiki/robotiq
diff --git a/robotiq_3f_gripper_joint_state_publisher/CMakeLists.txt b/robotiq_3f_gripper_joint_state_publisher/CMakeLists.txt
index 1449c931..90938ab3 100644
--- a/robotiq_3f_gripper_joint_state_publisher/CMakeLists.txt
+++ b/robotiq_3f_gripper_joint_state_publisher/CMakeLists.txt
@@ -2,12 +2,13 @@ cmake_minimum_required(VERSION 2.8.3)
project(robotiq_3f_gripper_joint_state_publisher)
## Find catkin macros and libraries
-find_package(catkin REQUIRED
+find_package(catkin REQUIRED COMPONENTS
+ message_generation
+ robotiq_3f_gripper_control
roscpp
roslib
sensor_msgs
- robotiq_3f_gripper_control
- )
+ )
###################################
## catkin specific configuration ##
@@ -18,7 +19,7 @@ find_package(catkin REQUIRED
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
- CATKIN_DEPENDS roscpp roslib sensor_msgs robotiq_3f_gripper_control
+ CATKIN_DEPENDS message_runtime robotiq_3f_gripper_control roscpp roslib sensor_msgs
)
###########
diff --git a/robotiq_3f_gripper_visualization/CMakeLists.txt b/robotiq_3f_gripper_visualization/CMakeLists.txt
index 8a3b31b7..85e3f85f 100644
--- a/robotiq_3f_gripper_visualization/CMakeLists.txt
+++ b/robotiq_3f_gripper_visualization/CMakeLists.txt
@@ -1,7 +1,7 @@
# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html
cmake_minimum_required(VERSION 2.8.3)
project(robotiq_3f_gripper_visualization)
-find_package(catkin REQUIRED urdf)
+find_package(catkin REQUIRED COMPONENTS urdf)
catkin_package()
install(DIRECTORY cfg DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
install(DIRECTORY meshes DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
diff --git a/robotiq_3f_rviz/CMakeLists.txt b/robotiq_3f_rviz/CMakeLists.txt
index 8744a096..a2c07ad1 100644
--- a/robotiq_3f_rviz/CMakeLists.txt
+++ b/robotiq_3f_rviz/CMakeLists.txt
@@ -128,7 +128,7 @@ include_directories(
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/robotiq_3f_rviz.cpp
# )
-add_library(${PROJECT_NAME} src/robotiq_3f_rviz.cpp)
+add_library(${PROJECT_NAME} src/${PROJECT_NAME}.cpp)
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
diff --git a/robotiq_ethercat/CMakeLists.txt b/robotiq_ethercat/CMakeLists.txt
index 09bb757f..187fc103 100644
--- a/robotiq_ethercat/CMakeLists.txt
+++ b/robotiq_ethercat/CMakeLists.txt
@@ -2,14 +2,14 @@ cmake_minimum_required(VERSION 2.8.3)
project(robotiq_ethercat)
find_package(catkin REQUIRED COMPONENTS
- soem
roscpp
+ soem
)
catkin_package(
INCLUDE_DIRS include
- LIBRARIES robotiq_ethercat
- CATKIN_DEPENDS soem roscpp
+ LIBRARIES ${PROJECT_NAME}
+ CATKIN_DEPENDS roscpp soem
)
include_directories(include
@@ -20,12 +20,12 @@ include_directories(include
${soem_INCLUDE_DIRS}/soem
)
-add_library(robotiq_ethercat
- include/robotiq_ethercat/ethercat_manager.h
+add_library(${PROJECT_NAME}
+ include/${PROJECT_NAME}/ethercat_manager.h
src/ethercat_manager.cpp
)
-install(TARGETS robotiq_ethercat
+install(TARGETS ${PROJECT_NAME}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
diff --git a/robotiq_ft_sensor/CMakeLists.txt b/robotiq_ft_sensor/CMakeLists.txt
index 25138092..24184351 100644
--- a/robotiq_ft_sensor/CMakeLists.txt
+++ b/robotiq_ft_sensor/CMakeLists.txt
@@ -2,9 +2,9 @@ cmake_minimum_required(VERSION 2.8.3)
project(robotiq_ft_sensor)
find_package(catkin REQUIRED COMPONENTS
+ message_generation
roscpp
std_msgs
- message_generation
)
diff --git a/robotiq_ft_sensor/package.xml b/robotiq_ft_sensor/package.xml
index b54dedaf..a3638a12 100644
--- a/robotiq_ft_sensor/package.xml
+++ b/robotiq_ft_sensor/package.xml
@@ -2,7 +2,7 @@
robotiq_ft_sensor1.0.0
- Package for reading data from a Robotiq Force Torque Sensor
+
Package for reading data from a Robotiq Force Torque Sensor
Jean-Philippe RobergeJonathan Savoiehttp://ros.org/wiki/robotiq
diff --git a/robotiq_modbus_rtu/CMakeLists.txt b/robotiq_modbus_rtu/CMakeLists.txt
index aa57b23b..afad4139 100644
--- a/robotiq_modbus_rtu/CMakeLists.txt
+++ b/robotiq_modbus_rtu/CMakeLists.txt
@@ -4,9 +4,9 @@ project(robotiq_modbus_rtu)
find_package(catkin REQUIRED COMPONENTS rospy)
#set the default path for built executables to the "bin" directory
-set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
+#set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
#set the default path for built libraries to the "lib" directory
-set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
+#set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
catkin_python_setup()
diff --git a/robotiq_modbus_tcp/CMakeLists.txt b/robotiq_modbus_tcp/CMakeLists.txt
index 63f5c2c5..22a9a157 100644
--- a/robotiq_modbus_tcp/CMakeLists.txt
+++ b/robotiq_modbus_tcp/CMakeLists.txt
@@ -4,9 +4,9 @@ project(robotiq_modbus_tcp)
find_package(catkin REQUIRED COMPONENTS rospy)
#set the default path for built executables to the "bin" directory
-set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
+#set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
#set the default path for built libraries to the "lib" directory
-set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
+#set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
catkin_python_setup()