diff --git a/industrial_deprecated/CMakeLists.txt b/industrial_deprecated/CMakeLists.txt
index af9ff096..1804e2d6 100644
--- a/industrial_deprecated/CMakeLists.txt
+++ b/industrial_deprecated/CMakeLists.txt
@@ -1,68 +1,10 @@
-# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html
cmake_minimum_required(VERSION 2.8.3)
-project(industrial_deprecated)
-# Load catkin and all dependencies required for this package
-find_package(catkin REQUIRED COMPONENTS rosgraph_msgs rospy)
-
-## System dependencies are found with CMake's conventions
-# find_package(Boost REQUIRED COMPONENTS system)
-find_package(Boost REQUIRED COMPONENTS system)
-
-# Python setup
-#catkin_python_setup()
-
-#Add unit test to check roslaunch dependencies.
-#rosbuild_add_roslaunch_check(launch)
-
-
-#######################################
-## Declare ROS messages and services ##
-#######################################
-
-## Generate messages in the 'msg' folder
-# add_message_files(
-# FILES
-# Message1.msg
-# Message2.msg
-# )
-## Generate services in the 'srv' folder
-# add_service_files(
-# FILES
-# Service1.srv
-# Service2.srv
-# )
-
-## Generate added messages and services with any dependencies listed here
-# generate_messages(
-# DEPENDENCIES
-# std_msgs
-# )
+project(industrial_deprecated)
+find_package(catkin REQUIRED COMPONENTS)
-###################################
-## catkin specific configuration ##
-###################################
-## The catkin_package macro generates cmake config files for your package
-## Declare things to be passed to dependent projects
-## LIBRARIES: libraries you create in this project that dependent projects also need
-## CATKIN_DEPENDS: catkin_packages dependent projects also need
-## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
- CATKIN_DEPENDS rosgraph_msgs rospy
+ CATKIN_DEPENDS
)
-#############
-## Install ##
-#############
-
-# all install targets should use catkin DESTINATION variables
-# See http://ros.org/doc/groovy/api/catkin/html/adv_user_guide/variables.html
-
-install(PROGRAMS scripts/fake_time.py
- DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-)
-
-install(DIRECTORY launch/
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
-)
diff --git a/industrial_deprecated/launch/planning_environment_visualization_prerequisites.launch b/industrial_deprecated/launch/planning_environment_visualization_prerequisites.launch
deleted file mode 100644
index f3593fb2..00000000
--- a/industrial_deprecated/launch/planning_environment_visualization_prerequisites.launch
+++ /dev/null
@@ -1,10 +0,0 @@
-
-
-
-
-
-
-
-
-
-
diff --git a/industrial_deprecated/package.xml b/industrial_deprecated/package.xml
index 4999e911..6b32d01d 100644
--- a/industrial_deprecated/package.xml
+++ b/industrial_deprecated/package.xml
@@ -2,10 +2,10 @@
industrial_deprecated
1.0.0
- The Industrial deprecated package contains nodes, launch files, etc... that are slated for
- deprecation. This package is the last place something will end up before being deleted.
- If you are missing a package/node and find it's contents here, then you should consider
- a replacement.
+ The Industrial deprecated package contains nodes, launch files, etc... that are slated for
+ deprecation. This package is the last place something will end up before being deleted.
+ If you are missing a package/node and find it's contents here, then you should consider
+ a replacement.
Shaun Edwards
BSD
@@ -13,8 +13,4 @@
Shaun M. Edwards
catkin
- rosgraph_msgs
- rospy
- rosgraph_msgs
- rospy
diff --git a/industrial_deprecated/scripts/fake_time.py b/industrial_deprecated/scripts/fake_time.py
deleted file mode 100755
index d52f35e0..00000000
--- a/industrial_deprecated/scripts/fake_time.py
+++ /dev/null
@@ -1,63 +0,0 @@
-#!/usr/bin/env python
-# Software License Agreement (BSD License)
-#
-# Copyright (c) 2010, Willow Garage, Inc.
-# All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# * Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# * Redistributions in binary form must reproduce the above
-# copyright notice, this list of conditions and the following
-# disclaimer in the documentation and/or other materials provided
-# with the distribution.
-# * Neither the name of Willow Garage, Inc. nor the names of its
-# contributors may be used to endorse or promote products derived
-# from this software without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
-# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-# Revision $Id: talker.py 5263 2009-07-17 23:30:38Z sfkwc $
-
-"""
-This publishes wall clock to the /clock topic to test simulated time routines
-"""
-
-import roslib;
-
-import time
-import rospy
-from rosgraph_msgs.msg import Clock
-
-def faketime():
- rospy.set_param('/use_sim_time', True)
- pub = rospy.Publisher('/clock', Clock)
- rospy.init_node('fake_time')
- c = Clock()
- while not rospy.is_shutdown():
- float_secs = time.time()
- secs = int(float_secs)
- c.clock.nsecs = int((float_secs - secs) * 1000000000)
- c.clock.secs = secs
- pub.publish(c)
- time.sleep(0.01)
-
-if __name__ == '__main__':
- try:
- faketime()
- except rospy.ROSInterruptException: pass
-
diff --git a/industrial_msgs/CMakeLists.txt b/industrial_msgs/CMakeLists.txt
index 95905b26..9c6523ee 100644
--- a/industrial_msgs/CMakeLists.txt
+++ b/industrial_msgs/CMakeLists.txt
@@ -1,14 +1,9 @@
-# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html
cmake_minimum_required(VERSION 2.8.3)
+
project(industrial_msgs)
-# Load catkin and all dependencies required for this package
-find_package(catkin REQUIRED COMPONENTS std_msgs trajectory_msgs genmsg message_generation)
-#######################################
-## Declare ROS messages and services ##
-#######################################
+find_package(catkin REQUIRED COMPONENTS std_msgs trajectory_msgs genmsg message_generation)
-## Generate messages in the 'msg' folder
add_message_files(
FILES
DebugLevel.msg
@@ -18,7 +13,6 @@ add_message_files(
ServiceReturnCode.msg
TriState.msg)
-## Generate services in the 'srv' folder
add_service_files(
FILES
CmdJointTrajectory.srv
@@ -28,21 +22,10 @@ add_service_files(
StartMotion.srv
StopMotion.srv)
-## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES trajectory_msgs std_msgs
)
-
-###################################
-## catkin specific configuration ##
-###################################
-## The catkin_package macro generates cmake config files for your package
-## Declare things to be passed to dependent projects
-## LIBRARIES: libraries you create in this project that dependent projects also need
-## CATKIN_DEPENDS: catkin_packages dependent projects also need
-## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
CATKIN_DEPENDS message_runtime std_msgs trajectory_msgs genmsg
-)
-
+)
\ No newline at end of file
diff --git a/industrial_robot_client/CMakeLists.txt b/industrial_robot_client/CMakeLists.txt
index e9e26de8..c9970f74 100644
--- a/industrial_robot_client/CMakeLists.txt
+++ b/industrial_robot_client/CMakeLists.txt
@@ -1,76 +1,39 @@
-# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html
cmake_minimum_required(VERSION 2.8.3)
+
project(industrial_robot_client)
-# Load catkin and all dependencies required for this package
-find_package(catkin REQUIRED COMPONENTS roscpp std_msgs sensor_msgs control_msgs trajectory_msgs simple_message actionlib_msgs actionlib urdf industrial_msgs industrial_utils)
-## System dependencies are found with CMake's conventions
-# find_package(Boost REQUIRED COMPONENTS system)
+find_package(catkin REQUIRED COMPONENTS roscpp std_msgs sensor_msgs
+ control_msgs trajectory_msgs simple_message actionlib_msgs actionlib
+ urdf industrial_msgs industrial_utils)
+
find_package(Boost REQUIRED COMPONENTS system thread)
# The definition is copied from the CMakeList for the simple_message package.
-add_definitions(-DROS=1) #build using ROS libraries
+add_definitions(-DROS=1) #build using ROS libraries
add_definitions(-DLINUXSOCKETS=1) #build using LINUX SOCKETS libraries
set(SRC_FILES src/joint_relay_handler.cpp
- src/robot_status_relay_handler.cpp
+ src/robot_status_relay_handler.cpp
src/joint_trajectory_downloader.cpp
src/joint_trajectory_streamer.cpp
src/joint_trajectory_interface.cpp
src/robot_state_interface.cpp
src/utils.cpp)
-#######################################
-## Declare ROS messages and services ##
-#######################################
-
-## Generate messages in the 'msg' folder
-# add_message_files(
-# FILES
-# Message1.msg
-# Message2.msg
-# )
-
-## Generate services in the 'srv' folder
-# add_service_files(
-# FILES
-# Service1.srv
-# Service2.srv
-# )
-
-## Generate added messages and services with any dependencies listed here
-# generate_messages(
-# DEPENDENCIES
-# std_msgs
-# )
-
-###################################
-## catkin specific configuration ##
-###################################
-## The catkin_package macro generates cmake config files for your package
-## Declare things to be passed to dependent projects
-## LIBRARIES: libraries you create in this project that dependent projects also need
-## CATKIN_DEPENDS: catkin_packages dependent projects also need
-## DEPENDS: system dependencies of this project that dependent projects also need
-
# NOTE: The libraries generated this package are not included in the catkin_package
# macro because libraries must be explicitly linked in projects that depend on this
# package. If this is not done (and these libraries were exported), then multiple
-# library definitions (normal - industrial_robot_client and byteswapped -
+# library definitions (normal - industrial_robot_client and byteswapped.
# industrial_robot_client_bswap) are both included (this is bad).
-
catkin_package(
- CATKIN_DEPENDS roscpp std_msgs sensor_msgs control_msgs trajectory_msgs simple_message actionlib_msgs actionlib urdf industrial_msgs industrial_utils
+ CATKIN_DEPENDS roscpp std_msgs sensor_msgs control_msgs trajectory_msgs
+ simple_message actionlib_msgs actionlib urdf industrial_msgs
+ industrial_utils
INCLUDE_DIRS include
)
-###########
-## Build ##
-###########
-## Specify additional locations of header files
-## Your package locations should be listed before other locations
include_directories(include
${catkin_INCLUDE_DIRS}
)
@@ -82,12 +45,12 @@ include_directories(include
# passthrough of binary numeric data to the robot controller, and one that
# uses byte-swapping to account for endian mis-matches.
#
-# Due to rosmake dependency limitations, higher-level code must explicitly
-# link to the desired industrial_robot_client library:
+# Due to catkin dependency limitations, higher-level code must
+# explicitly link to the desired industrial_robot_client library:
# target_link_libraries(my_node industrial_robot_client)
# or
# target_link_libraries(my_node industrial_robot_client_bswap)
-
+#
add_library(industrial_robot_client ${SRC_FILES})
target_link_libraries(industrial_robot_client simple_message)
@@ -95,7 +58,6 @@ target_link_libraries(industrial_robot_client simple_message)
add_library(industrial_robot_client_bswap ${SRC_FILES})
target_link_libraries(industrial_robot_client_bswap simple_message_bswap)
-
# The following executables(nodes) are for applications where the robot
# controller and pc have the same byte order (i.e. byte swapping NOT
# required)
@@ -175,9 +137,6 @@ target_link_libraries(utest_robot_client
##find_package(roslaunch)
##roslaunch_add_file_check(launch)
-#############
-## Install ##
-#############
install(
TARGETS industrial_robot_client industrial_robot_client_bswap
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
diff --git a/industrial_robot_simulator/CMakeLists.txt b/industrial_robot_simulator/CMakeLists.txt
index cef7ad24..cc4fc63c 100644
--- a/industrial_robot_simulator/CMakeLists.txt
+++ b/industrial_robot_simulator/CMakeLists.txt
@@ -1,20 +1,10 @@
-# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html
cmake_minimum_required(VERSION 2.8.3)
+
project(industrial_robot_simulator)
-# Load catkin and all dependencies required for this package
-find_package(catkin REQUIRED COMPONENTS roscpp std_msgs sensor_msgs control_msgs trajectory_msgs industrial_robot_client)
-
-# Python setup
-#catkin_python_setup()
-
-###################################
-## catkin specific configuration ##
-###################################
-## The catkin_package macro generates cmake config files for your package
-## Declare things to be passed to dependent projects
-## LIBRARIES: libraries you create in this project that dependent projects also need
-## CATKIN_DEPENDS: catkin_packages dependent projects also need
-## DEPENDS: system dependencies of this project that dependent projects also need
+
+find_package(catkin REQUIRED COMPONENTS roscpp std_msgs sensor_msgs
+ control_msgs trajectory_msgs industrial_robot_client)
+
catkin_package(
CATKIN_DEPENDS roscpp std_msgs sensor_msgs control_msgs trajectory_msgs industrial_robot_client
)
@@ -33,8 +23,6 @@ catkin_package(
## Install ##
#############
-# all install targets should use catkin DESTINATION variables
-# See http://ros.org/doc/groovy/api/catkin/html/adv_user_guide/variables.html
install(PROGRAMS industrial_robot_simulator DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
diff --git a/industrial_trajectory_filters/CMakeLists.txt b/industrial_trajectory_filters/CMakeLists.txt
index 7911f47d..88d77a3d 100644
--- a/industrial_trajectory_filters/CMakeLists.txt
+++ b/industrial_trajectory_filters/CMakeLists.txt
@@ -1,5 +1,5 @@
-# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html
cmake_minimum_required(VERSION 2.8.3)
+
project(industrial_trajectory_filters)
find_package(catkin REQUIRED COMPONENTS moveit_ros_planning trajectory_msgs)
@@ -7,24 +7,18 @@ find_package(catkin REQUIRED COMPONENTS moveit_ros_planning trajectory_msgs)
catkin_package(
CATKIN_DEPENDS moveit_ros_planning trajectory_msgs
INCLUDE_DIRS include
- LIBRARIES ${MOVEIT_LIB_NAME}
+ LIBRARIES ${PROJECT_NAME}
)
include_directories(include
${catkin_INCLUDE_DIRS}
)
-###########
-## Build ##
-###########
add_library(${PROJECT_NAME} src/n_point_filter.cpp src/uniform_sample_filter.cpp)
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
-#############
-## Install ##
-#############
install(TARGETS ${PROJECT_NAME}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
diff --git a/industrial_utils/CMakeLists.txt b/industrial_utils/CMakeLists.txt
index 6c1ea237..cac163fe 100644
--- a/industrial_utils/CMakeLists.txt
+++ b/industrial_utils/CMakeLists.txt
@@ -1,69 +1,30 @@
-# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html
cmake_minimum_required(VERSION 2.8.3)
+
project(industrial_utils)
-# Load catkin and all dependencies required for this package
+
find_package(catkin REQUIRED COMPONENTS roscpp urdf)
-## System dependencies are found with CMake's conventions
-# find_package(Boost REQUIRED COMPONENTS system)
find_package(Boost REQUIRED COMPONENTS system)
-#######################################
-## Declare ROS messages and services ##
-#######################################
-
-## Generate messages in the 'msg' folder
-# add_message_files(
-# FILES
-# Message1.msg
-# Message2.msg
-# )
-
-## Generate services in the 'srv' folder
-# add_service_files(
-# FILES
-# Service1.srv
-# Service2.srv
-# )
-
-## Generate added messages and services with any dependencies listed here
-# generate_messages(
-# DEPENDENCIES
-# std_msgs
-# )
-
-###################################
-## catkin specific configuration ##
-###################################
-## The catkin_package macro generates cmake config files for your package
-## Declare things to be passed to dependent projects
-## LIBRARIES: libraries you create in this project that dependent projects also need
-## CATKIN_DEPENDS: catkin_packages dependent projects also need
-## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
CATKIN_DEPENDS roscpp urdf
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME}
)
-###########
-## Build ##
-###########
-
-## Specify additional locations of header files
-## Your package locations should be listed before other locations
include_directories(include
${catkin_INCLUDE_DIRS})
add_library(${PROJECT_NAME} src/utils.cpp src/param_utils.cpp)
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
+
+
catkin_add_gtest(utest_inds_utils test/utest.cpp)
target_link_libraries(utest_inds_utils ${PROJECT_NAME} ${catkin_LIBRARIES})
-#############
-## Install ##
-#############
+
+
install(
TARGETS ${PROJECT_NAME}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
diff --git a/simple_message/CMakeLists.txt b/simple_message/CMakeLists.txt
index 435e82e5..2efdbf5b 100644
--- a/simple_message/CMakeLists.txt
+++ b/simple_message/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(simple_message)
-# Load catkin and all dependencies required for this package
+
find_package(catkin REQUIRED COMPONENTS roscpp industrial_msgs)
# Build static libs, to reduce dependency-chaining for industrial_robot_client
@@ -12,7 +12,7 @@ set(ROS_BUILD_SHARED_LIBS false)
# and various robot controllers. This requires conditionally compiling
# certain functions and headers. The definition below enables compiling
# for a ROS node.
-add_definitions(-DROS=1) #build using ROS libraries
+add_definitions(-DROS=1) #build using ROS libraries
add_definitions(-DLINUXSOCKETS=1) #use linux sockets for communication
set(SRC_FILES src/byte_array.cpp
@@ -61,15 +61,6 @@ set(UTEST_SRC_FILES test/utest.cpp test/utest_message.cpp)
# controllers). This library performs byte swapping at the lowest load/unload
# levels.
-###################################
-## catkin specific configuration ##
-###################################
-## The catkin_package macro generates cmake config files for your package
-## Declare things to be passed to dependent projects
-## LIBRARIES: libraries you create in this project that dependent projects also need
-## CATKIN_DEPENDS: catkin_packages dependent projects also need
-## DEPENDS: system dependencies of this project that dependent projects also need
-
# NOTE: The libraries generated this package are not included in the catkin_package
# macro because libraries must be explicitly linked in projects that depend on this
# package. If this is not done (and these libraries were exported), then multiple
@@ -81,12 +72,7 @@ catkin_package(
INCLUDE_DIRS include
)
-###########
-## Build ##
-###########
-## Specify additional locations of header files
-## Your package locations should be listed before other locations
include_directories(include
${catkin_INCLUDE_DIRS}
)
@@ -124,9 +110,7 @@ set_target_properties(utest_float64 PROPERTIES COMPILE_DEFINITIONS "TEST_PORT_BA
target_link_libraries(utest_float64 simple_message_float64)
-#############
-## Install ##
-#############
+
install(
TARGETS simple_message simple_message_bswap simple_message_float64
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
@@ -134,3 +118,4 @@ install(
install(
DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})
+