diff --git a/caljob_creator/CMakeLists.txt b/caljob_creator/CMakeLists.txt
index fd8333cd..696e3d92 100644
--- a/caljob_creator/CMakeLists.txt
+++ b/caljob_creator/CMakeLists.txt
@@ -1,9 +1,6 @@
cmake_minimum_required(VERSION 2.8.3)
project(caljob_creator)
-## Find catkin macros and libraries
-## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
-## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
cv_bridge
image_transport
@@ -12,156 +9,43 @@ find_package(catkin REQUIRED COMPONENTS
std_msgs
tf
)
-FIND_PACKAGE(OpenCV REQUIRED)
-## System dependencies are found with CMake's conventions
-# find_package(Boost REQUIRED COMPONENTS system)
+find_package(OpenCV 2 REQUIRED)
-## Uncomment this if the package has a setup.py. This macro ensures
-## modules and global scripts declared therein get installed
-## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
-# catkin_python_setup()
-
-################################################
-## Declare ROS messages, services and actions ##
-################################################
-
-## To declare and build messages, services or actions from within this
-## package, follow these steps:
-## * Let MSG_DEP_SET be the set of packages whose message types you use in
-## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
-## * In the file package.xml:
-## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
-## * If MSG_DEP_SET isn't empty the following dependencies might have been
-## pulled in transitively but can be declared for certainty nonetheless:
-## * add a build_depend tag for "message_generation"
-## * add a run_depend tag for "message_runtime"
-## * In this file (CMakeLists.txt):
-## * add "message_generation" and every package in MSG_DEP_SET to
-## find_package(catkin REQUIRED COMPONENTS ...)
-## * add "message_runtime" and every package in MSG_DEP_SET to
-## catkin_package(CATKIN_DEPENDS ...)
-## * uncomment the add_*_files sections below as needed
-## and list every .msg/.srv/.action file to be processed
-## * uncomment the generate_messages entry below
-## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
-
-## 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 actions in the 'action' folder
-# add_action_files(
-# FILES
-# Action1.action
-# Action2.action
-# )
-
-## Generate added messages and services with any dependencies listed here
-# generate_messages(
-# DEPENDENCIES
-# sensor_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
-## INCLUDE_DIRS: uncomment this if you package contains header files
-## 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(
-# INCLUDE_DIRS include
-# LIBRARIES caljob_creator
-# CATKIN_DEPENDS cv_bridge image_transport roscpp sensor_msgs std_msgs
-# DEPENDS system_lib
+ CATKIN_DEPENDS
+ cv_bridge
+ image_transport
+ roscpp
+ sensor_msgs
+ std_msgs
+ tf
+ DEPENDS
+ OpenCV
)
-###########
-## Build ##
-###########
-
-## Specify additional locations of header files
-## Your package locations should be listed before other locations
-# include_directories(include)
include_directories(
+ ${OpenCV_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
)
-## Declare a cpp library
-# add_library(caljob_creator
-# src/${PROJECT_NAME}/caljob_creator.cpp
-# )
-## Declare a cpp executable
add_executable(caljob_creator_node src/main.cpp)
+add_dependencies(caljob_creator_node ${catkin_EXPORTED_TARGETS})
+target_link_libraries(caljob_creator_node ${OpenCV_LIBRARIES} ${catkin_LIBRARIES})
-## Add cmake target dependencies of the executable/library
-## as an example, message headers may need to be generated before nodes
-# add_dependencies(caljob_creator_node caljob_creator_generate_messages_cpp)
-## Specify libraries to link a library or executable target against
-target_link_libraries(caljob_creator_node
- ${catkin_LIBRARIES}
+install(
+ TARGETS
+ caljob_creator_node
+ RUNTIME DESTINATION
+ ${CATKIN_PACKAGE_BIN_DESTINATION}
)
-#############
-## Install ##
-#############
-
-# all install targets should use catkin DESTINATION variables
-# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
-
-## Mark executable scripts (Python etc.) for installation
-## in contrast to setup.py, you can choose the destination
-# install(PROGRAMS
-# scripts/my_python_script
-# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-# )
-
-## Mark executables and/or libraries for installation
-# install(TARGETS caljob_creator caljob_creator_node
-# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
-# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
-# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-# )
-
-## Mark cpp header files for installation
-# install(DIRECTORY include/${PROJECT_NAME}/
-# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
-# FILES_MATCHING PATTERN "*.h"
-# PATTERN ".svn" EXCLUDE
-# )
-
-## Mark other files for installation (e.g. launch and bag files, etc.)
-# install(FILES
-# # myfile1
-# # myfile2
-# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
-# )
-
-#############
-## Testing ##
-#############
-
-## Add gtest based cpp test target and link libraries
-# catkin_add_gtest(${PROJECT_NAME}-test test/test_caljob_creator.cpp)
-# if(TARGET ${PROJECT_NAME}-test)
-# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
-# endif()
-
-## Add folders to be run by python nosetests
-# catkin_add_nosetests(test)
+install(
+ DIRECTORY
+ launch
+ DESTINATION
+ ${CATKIN_PACKAGE_SHARE_DESTINATION}
+)
diff --git a/caljob_creator/package.xml b/caljob_creator/package.xml
index a637bf8c..225349b1 100644
--- a/caljob_creator/package.xml
+++ b/caljob_creator/package.xml
@@ -1,63 +1,31 @@
caljob_creator
- 0.0.0
- The caljob_creator package
+ 0.1.0
+
+ The calibration job creator.
+
+ Chris Lewis
+ Chris Lewis
+ Apache2.0
+
+ http://wiki.ros.org/caljob_creator
+ https://github.com/ros-industrial/industrial_calibration/issues
+ https://github.com/ros-industrial/industrial_calibration
-
-
-
- jon
-
-
-
-
-
- TODO
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
catkin
+
cv_bridge
image_transport
roscpp
sensor_msgs
std_msgs
+ tf
+
cv_bridge
image_transport
roscpp
sensor_msgs
std_msgs
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
+ tf
+
diff --git a/industrial_extrinsic_cal/CMakeLists.txt b/industrial_extrinsic_cal/CMakeLists.txt
index 63e40b6f..e78d7c5e 100644
--- a/industrial_extrinsic_cal/CMakeLists.txt
+++ b/industrial_extrinsic_cal/CMakeLists.txt
@@ -1,229 +1,243 @@
cmake_minimum_required(VERSION 2.8.3)
project(industrial_extrinsic_cal)
-## Find catkin macros and libraries
-## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
-## is used, also find other catkin packages
-find_package(catkin REQUIRED COMPONENTS roscpp std_msgs cv_bridge tf roslint std_srvs roslib genmsg actionlib_msgs actionlib moveit_ros_planning_interface geometry_msgs sensor_msgs)
-
-# Opencv
-FIND_PACKAGE(OpenCV REQUIRED)
-IF (OPENCV_FOUND)
- MESSAGE("-- Found OpenCV version ${OPENCV_VERSION}: ${OPENCV_INCLUDE_DIRS}")
-ENDIF (OPENCV_FOUND)
-
-# Ceres
-FIND_PACKAGE(Ceres REQUIRED)
-IF (CERES_FOUND)
- MESSAGE("-- Found Ceres version ${CERES_VERSION}: ${CERES_INCLUDE_DIRS}")
-ENDIF (CERES_FOUND)
-
-SET (CMAKE_CXX_FLAGS -fPIC)
-
-# Eigen
-#FIND_PACKAGE(Eigen REQUIRED)
-#IF (EIGEN_FOUND)
-# MESSAGE("-- Found Eigen version ${EIGEN_VERSION}: ${EIGEN_INCLUDE_DIRS}")
-#ENDIF (EIGEN_FOUND)
-
-## System dependencies are found with CMake's conventions
-# find_package(Boost REQUIRED COMPONENTS system)
-
-## Uncomment this if the package has a setup.py. This macro ensures
-## modules and global scripts declared therein get installed
-## See http://ros.org/doc/groovy/api/catkin/html/user_guide/setup_dot_py.html
-# catkin_python_setup()
-
-#######################################
-## 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
- get_mutable_joint_states.srv
- set_mutable_joint_states.srv
- store_mutable_joint_states.srv
- camera_observer_trigger.srv
- user_accept.srv
- calibrate.srv
- covariance.srv
- )
-
-add_action_files(DIRECTORY action FILES manual_trigger.action robot_joint_values_trigger.action robot_pose_trigger.action manual_target_location.action calibration.action)
-
-## Generate added messages and services with any dependencies listed here
-# generate_messages(
-# DEPENDENCIES
-# std_msgs # Or other packages containing msgs
-# )
+find_package(catkin REQUIRED COMPONENTS
+ actionlib
+ actionlib_msgs
+ cv_bridge
+ geometry_msgs
+ image_transport
+ message_generation
+ moveit_ros_planning_interface
+ rosconsole
+ roscpp
+ roslib
+ roslint
+ sensor_msgs
+ std_msgs
+ std_srvs
+ tf
+ tf_conversions
+)
+
+#set(CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} "-fPIC")
+
+
+find_package(Boost REQUIRED)
+
+find_package(Ceres REQUIRED)
+message("-- Found Ceres version ${CERES_VERSION}: ${CERES_INCLUDE_DIRS}")
+
+find_package(OpenCV 2 REQUIRED)
+message("-- Found OpenCV version ${OpenCV_VERSION}: ${OpenCV_INCLUDE_DIRS}")
+
+find_package(PkgConfig REQUIRED)
+pkg_check_modules(yaml_cpp REQUIRED yaml-cpp)
+if(NOT ${yaml_cpp_VERSION} VERSION_LESS "0.5")
+ add_definitions(-DHAVE_NEW_YAMLCPP)
+endif()
+
+find_path(
+ yaml_cpp_INCLUDE_DIR
+ # bit of a trick
+ NAMES yaml-cpp/yaml.h
+ PATHS ${yaml_cpp_INCLUDE_DIRS}
+)
+
+find_library(
+ yaml_cpp_LIBRARY
+ NAMES ${yaml_cpp_LIBRARIES}
+ PATHS ${yaml_cpp_LIBRARY_DIRS}
+)
+
+#message("yaml_cpp_INCLUDE_DIRS: ${yaml_cpp_INCLUDE_DIRS}")
+#message("yaml_cpp_INCLUDE_DIR: ${yaml_cpp_INCLUDE_DIR}")
+#message("yaml_cpp_LIBRARY: ${yaml_cpp_LIBRARY}")
+
+
+add_service_files(
+ FILES
+ calibrate.srv
+ camera_observer_trigger.srv
+ covariance.srv
+ get_mutable_joint_states.srv
+ set_mutable_joint_states.srv
+ store_mutable_joint_states.srv
+ user_accept.srv
+)
+
+add_action_files(
+ DIRECTORY
+ action
+ FILES
+ calibration.action
+ manual_target_location.action
+ manual_trigger.action
+ robot_joint_values_trigger.action
+ robot_pose_trigger.action
+)
generate_messages(
- DEPENDENCIES
- std_msgs
- geometry_msgs
- actionlib_msgs
+ DEPENDENCIES
+ actionlib_msgs
+ geometry_msgs
sensor_msgs
+ std_msgs
)
-set(CMAKE_CXX_FLAGS ${CMAKE_CSS_FLAGS} "-fPIC")
-###################################
-## 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(
- INCLUDE_DIRS include /usr/include/eigen3
-# LIBRARIES
- CATKIN_DEPENDS roscpp std_msgs rosconsole std_srvs roslib
-# DEPENDS
+ LIBRARIES
+ industrial_extrinsic_cal
+ INCLUDE_DIRS
+ include
+ CATKIN_DEPENDS
+ actionlib
+ actionlib_msgs
+ cv_bridge
+ geometry_msgs
+ image_transport
+ message_runtime
+ moveit_ros_planning_interface
+ rosconsole
+ roscpp
+ roslib
+ roslint
+ sensor_msgs
+ std_msgs
+ std_srvs
+ tf
+ tf_conversions
+ DEPENDS
+ Boost
+ CERES
)
-###########
-## Build ##
-###########
-## Specify additional locations of header files
-## Your package locations should be listed before other locations
-include_directories(include
-# ${catkin_INCLUDE_DIRS} ${EIGEN_INCLUDE_DIRS} ${CERES_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS}
- ${catkin_INCLUDE_DIRS} ${CERES_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS}
-)
-## Declare a cpp library
-# For Example:
-# add_library(industrial_extrinsic_cal src/${PROJECT_NAME}/industrial_extrinsic_cal.cpp)
-#
-add_library(industrial_extrinsic_cal
- src/ros_camera_observer.cpp
- src/camera_definition.cpp
- src/target.cpp
- src/observation_scene.cpp
- src/observation_data_point.cpp
- src/ceres_blocks.cpp
- src/basic_types.cpp
- src/ros_transform_interface.cpp
- src/ceres_costs_utils.cpp
- src/circle_detector.cpp
- src/camera_yaml_parser.cpp
- src/targets_yaml_parser.cpp
- src/points_yaml_parser.cpp
- src/caljob_yaml_parser.cpp
- src/calibration_job_definition.cpp
+include_directories(
+ include
+ ${catkin_INCLUDE_DIRS}
+ ${CERES_INCLUDE_DIRS}
+ ${OpenCV_INCLUDE_DIRS}
+ ${yaml_cpp_INCLUDE_DIR}
)
-## This insures the creation of headers for all ros messages, services and actions
+
+# target: main library
+add_library(
+ industrial_extrinsic_cal
+
+ src/basic_types.cpp
+ src/calibration_job_definition.cpp
+ src/caljob_yaml_parser.cpp
+ src/camera_definition.cpp
+ src/camera_yaml_parser.cpp
+ src/ceres_blocks.cpp
+ src/ceres_costs_utils.cpp
+ src/circle_detector.cpp
+ src/observation_data_point.cpp
+ src/observation_scene.cpp
+ src/points_yaml_parser.cpp
+ src/ros_camera_observer.cpp
+ src/ros_transform_interface.cpp
+ src/target.cpp
+ src/targets_yaml_parser.cpp
+)
add_dependencies(industrial_extrinsic_cal ${PROJECT_NAME}_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
+target_link_libraries(
+ industrial_extrinsic_cal
-## Declare a cpp executable
-add_executable(manual_calt_adjust src/nodes/manual_calt_adjuster.cpp)
-add_executable(nist_analysis src/nodes/nist_analysis.cpp)
-add_executable(mono_ex_cal src/nodes/mono_ex_cal.cpp)
-add_executable(service_node src/nodes/calibration_service.cpp )
-add_executable(trigger_service src/nodes/ros_scene_trigger_server.cpp)
+ ${yaml_cpp_LIBRARY}
+ ${catkin_LIBRARIES}
+ ${OpenCV_LIBRARIES}
+ ${CERES_LIBRARIES}
+)
+
+
+# targets: other nodes
+add_executable(camera_observer_scene_trigger src/nodes/camera_observer_scene_trigger.cpp)
+add_executable(manual_calt_adjust src/nodes/manual_calt_adjuster.cpp)
+add_executable(mono_ex_cal src/nodes/mono_ex_cal.cpp)
+add_executable(mutable_joint_state_publisher src/nodes/mutable_joint_state_publisher.cpp)
+add_executable(nist_analysis src/nodes/nist_analysis.cpp)
add_executable(ros_robot_trigger_action_service src/nodes/ros_robot_scene_trigger_action_server.cpp)
-add_executable(mutable_joint_state_publisher src/nodes/mutable_joint_state_publisher.cpp)
-add_executable(camera_observer_scene_trigger src/nodes/camera_observer_scene_trigger.cpp)
-
-## These insure the message, action and service headers are created first
-add_dependencies(service_node ${PROJECT_NAME}_generate_messages_cpp )
-add_dependencies(trigger_service ${PROJECT_NAME}_generate_messages_cpp )
-add_dependencies(ros_robot_trigger_action_service ${PROJECT_NAME}_generate_messages_cpp)
-add_dependencies(mutable_joint_state_publisher ${PROJECT_NAME}_generate_messages_cpp)
-add_dependencies(camera_observer_scene_trigger ${PROJECT_NAME}_generate_messages_cpp)
-
-## Add cmake target dependencies of the executable/library
-## as an example, message headers may need to be generated before nodes
-# add_dependencies(industrial_extrinsic_cal_node industrial_extrinsic_cal_generate_messages_cpp)
-
-## Specify libraries to link a library or executable target against
-target_link_libraries(manual_calt_adjust industrial_extrinsic_cal ${catkin_LIBRARIES} )
-target_link_libraries(nist_analysis industrial_extrinsic_cal ${catkin_LIBRARIES} ${CERES_LIBRARIES} )
-target_link_libraries(industrial_extrinsic_cal yaml-cpp ${catkin_LIBRARIES} ${OpenCV_LIBRARIES} ${CERES_LIBRARIES})
-target_link_libraries(mono_ex_cal ${catkin_LIBRARIES} ${CERES_LIBRARIES} )
-
-#target_link_libraries(test_obs industrial_extrinsic_cal yaml-cpp ${catkin_LIBRARIES} ${CERES_LIBRARIES})
-target_link_libraries(service_node industrial_extrinsic_cal ${CERES_LIBRARIES} )
-target_link_libraries(trigger_service ${catkin_LIBRARIES} )
-target_link_libraries(ros_robot_trigger_action_service ${catkin_LIBRARIES} )
-target_link_libraries(mutable_joint_state_publisher ${catkin_LIBRARIES} yaml-cpp )
-target_link_libraries(camera_observer_scene_trigger industrial_extrinsic_cal ${catkin_LIBRARIES} yaml-cpp )
-catkin_add_gtest(utest_inds_cal test/utest.cpp)
-target_link_libraries(utest_inds_cal ${PROJECT_NAME} industrial_extrinsic_cal ${catkin_LIBRARIES} ${CERES_LIBRARIES})
-
-add_dependencies(ros_robot_trigger_action_service ${catkin_EXPORTED_TARGETS})
-
-#############
-## Install ##
-#############
-
-# all install targets should use catkin DESTINATION variables
-# See http://ros.org/doc/groovy/api/catkin/html/adv_user_guide/variables.html
-
-## Mark executable scripts (Python etc.) for installation
-## in contrast to setup.py, you can choose the destination
-# install(PROGRAMS
-# scripts/my_python_script
-# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-# )
-
-## Mark executables and/or libraries for installation
-# install(TARGETS industrial_extrinsic_cal industrial_extrinsic_cal_node
-# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
-# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
-# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-# )
-
-## Mark cpp header files for installation
-# install(DIRECTORY include/${PROJECT_NAME}/
-# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
-# FILES_MATCHING PATTERN "*.h"
-# PATTERN ".svn" EXCLUDE
-# )
-
-## Mark other files for installation (e.g. launch and bag files, etc.)
-# install(FILES
-# # myfile1
-# # myfile2
-# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
-# )
-
-#############
-## Testing ##
-#############
-
-## Add gtest based cpp test target and link libraries
-# catkin_add_gtest(${PROJECT_NAME}-test test/test_industrial_extrinsic_cal.cpp)
-# if(TARGET ${PROJECT_NAME}-test)
-# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
-# endif()
-
-## Add folders to be run by python nosetests
-# catkin_add_nosetests(test)
+add_executable(service_node src/nodes/calibration_service.cpp)
+add_executable(trigger_service src/nodes/ros_scene_trigger_server.cpp)
+
+add_dependencies(camera_observer_scene_trigger ${catkin_EXPORTED_TARGETS} ${industrial_extrinsic_cal_EXPORTED_TARGETS})
+add_dependencies(mutable_joint_state_publisher ${catkin_EXPORTED_TARGETS} ${industrial_extrinsic_cal_EXPORTED_TARGETS})
+add_dependencies(ros_robot_trigger_action_service ${catkin_EXPORTED_TARGETS} ${industrial_extrinsic_cal_EXPORTED_TARGETS})
+add_dependencies(service_node ${catkin_EXPORTED_TARGETS} ${industrial_extrinsic_cal_EXPORTED_TARGETS})
+add_dependencies(trigger_service ${catkin_EXPORTED_TARGETS} ${industrial_extrinsic_cal_EXPORTED_TARGETS})
+
+target_link_libraries(camera_observer_scene_trigger industrial_extrinsic_cal ${catkin_LIBRARIES} ${yaml_cpp_LIBRARY} ${CERES_LIBRARIES})
+target_link_libraries(manual_calt_adjust industrial_extrinsic_cal ${catkin_LIBRARIES})
+target_link_libraries(mono_ex_cal ${catkin_LIBRARIES} ${CERES_LIBRARIES})
+target_link_libraries(mutable_joint_state_publisher ${catkin_LIBRARIES} ${yaml_cpp_LIBRARY})
+target_link_libraries(nist_analysis industrial_extrinsic_cal ${catkin_LIBRARIES} ${CERES_LIBRARIES})
+target_link_libraries(ros_robot_trigger_action_service ${catkin_LIBRARIES})
+target_link_libraries(service_node industrial_extrinsic_cal ${CERES_LIBRARIES})
+#target_link_libraries(test_obs industrial_extrinsic_cal ${yaml_cpp_LIBRARY} ${catkin_LIBRARIES} ${CERES_LIBRARIES})
+target_link_libraries(trigger_service ${catkin_LIBRARIES})
+
+
+install(
+ TARGETS
+ camera_observer_scene_trigger
+ industrial_extrinsic_cal
+ manual_calt_adjust
+ mono_ex_cal
+ mutable_joint_state_publisher
+ nist_analysis
+ ros_robot_trigger_action_service
+ service_node
+ trigger_service
+ ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+ LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+ RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+)
+
+install(
+ DIRECTORY
+ include/${PROJECT_NAME}
+ DESTINATION
+ ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
+)
+
+install(
+ DIRECTORY
+ config launch targets urdf yaml
+ DESTINATION
+ ${CATKIN_PACKAGE_SHARE_DESTINATION}
+)
+
+
+if (CATKIN_ENABLE_TESTING)
+ catkin_add_gtest(utest_inds_cal test/utest.cpp)
+
+ target_link_libraries(
+ utest_inds_cal
+
+ industrial_extrinsic_cal
+ ${catkin_LIBRARIES}
+ ${CERES_LIBRARIES}
+ )
+endif()
+
## ROSlint checks
## For more information see: http://wiki.ros.org/roslint
##
## CPPlint options justifications
## - whitespace/* - errors are ignored, it is assumed that the follwing eclipse
-## format file has been applied:
+## format file has been applied:
## http://wiki.ros.org/IDEs?action=AttachFile&do=get&target=ROS_format.xml
## - build/header_guard - #ifdef/#ifndef naming doesn't match ROS sytle
## - readability/stream - does not apply to logging (the typical use in ROS)
## - runtime/references - pass by reference is allowed for output parameters
-set(ROSLINT_CPP_OPTS
-"--filter=-whitespace,-build/header_guard,-build/include_order,-readability/streams,-runtime/references")
-file(GLOB_RECURSE ${PROJECT_NAME}_LINT_SRCS
+set(ROSLINT_CPP_OPTS
+ "--filter=-whitespace,-build/header_guard,-build/include_order,-readability/streams,-runtime/references")
+file(GLOB_RECURSE ${PROJECT_NAME}_LINT_SRCS
RELATIVE ${PROJECT_SOURCE_DIR} src/*.cpp include/*.h)
roslint_cpp(${${PROJECT_NAME}_LINT_SRCS})
diff --git a/industrial_extrinsic_cal/package.xml b/industrial_extrinsic_cal/package.xml
index ce0dbffb..8cfed513 100644
--- a/industrial_extrinsic_cal/package.xml
+++ b/industrial_extrinsic_cal/package.xml
@@ -1,75 +1,65 @@
industrial_extrinsic_cal
- 0.0.0
- The industrial_extrinsic_cal package
-
-
-
-
- clewis
-
-
-
-
-
- Apache
-
-
-
-
-
-
-
-
-
-
-
-
+ 0.1.0
+
+ Extrinsic calibration.
+
Chris Lewis
+ Chris Lewis
+ Apache2.0
+
+ http://wiki.ros.org/industrial_extrinsic_cal
+ https://github.com/ros-industrial/industrial_calibration/issues
+ https://github.com/ros-industrial/industrial_calibration
-
-
-
-
-
-
-
-
-
-
-
catkin
- roscpp
- std_msgs
- rosconsole
- std_srvs
- roslib
- roslint
+ pkg-config
+
actionlib
actionlib_msgs
+ boost
+ cv_bridge
geometry_msgs
- sensor_msgs
+ image_transport
+ message_generation
moveit_ros_planning_interface
+ rosconsole
+ roscpp
+ roslib
+ roslint
+ sensor_msgs
+ std_msgs
+ std_srvs
+ tf
+ tf_conversions
+ yaml-cpp
- roscpp
- std_msgs
- rosconsole
- std_srvs
- roslib
actionlib
actionlib_msgs
+ camera_aravis
+ cv_bridge
geometry_msgs
- sensor_msgs
+ image_transport
+ image_view
+ message_runtime
+ motoman_driver
+ motoman_sia20d_support
moveit_ros_planning_interface
+ nodelet
+ openni2_launch
+ robot_state_publisher
+ rosconsole
+ roscpp
+ roslib
+ roslint
+ rviz
+ sensor_msgs
+ std_msgs
+ std_srvs
+ tf
+ tf_conversions
+ yaml-cpp
-
-
-
-
-
-
-
-
-
+ rosunit
diff --git a/intrinsic_cal/CMakeLists.txt b/intrinsic_cal/CMakeLists.txt
index 0e50c8be..eec39af8 100644
--- a/intrinsic_cal/CMakeLists.txt
+++ b/intrinsic_cal/CMakeLists.txt
@@ -1,182 +1,78 @@
cmake_minimum_required(VERSION 2.8.3)
project(intrinsic_cal)
-## Find catkin macros and libraries
-## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
-## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
+ geometry_msgs
industrial_extrinsic_cal
+ message_generation
+ rosconsole
roscpp
- rospy
- std_msgs
- std_srvs
roslib
- genmsg
- geometry_msgs
+ std_msgs
+ std_srvs
+)
+
+find_package(Ceres REQUIRED)
+message("-- Found Ceres version ${CERES_VERSION}: ${CERES_INCLUDE_DIRS}")
+
+#set(CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} "-fPIC")
+
+
+add_service_files(
+ FILES
+ rail_ical_run.srv
)
-## System dependencies are found with CMake's conventions
-# find_package(Boost REQUIRED COMPONENTS system)
-
-# Ceres
-FIND_PACKAGE(Ceres REQUIRED)
-IF (CERES_FOUND)
- MESSAGE("-- Found Ceres version ${CERES_VERSION}: ${CERES_INCLUDE_DIRS}")
-ENDIF (CERES_FOUND)
-
-SET (CMAKE_CXX_FLAGS -fPIC)
-
-
-
-## Uncomment this if the package has a setup.py. This macro ensures
-## modules and global scripts declared therein get installed
-## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
-# catkin_python_setup()
-
-################################################
-## Declare ROS messages, services and actions ##
-################################################
-
-## To declare and build messages, services or actions from within this
-## package, follow these steps:
-## * Let MSG_DEP_SET be the set of packages whose message types you use in
-## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
-## * In the file package.xml:
-## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
-## * If MSG_DEP_SET isn't empty the following dependencies might have been
-## pulled in transitively but can be declared for certainty nonetheless:
-## * add a build_depend tag for "message_generation"
-## * add a run_depend tag for "message_runtime"
-## * In this file (CMakeLists.txt):
-## * add "message_generation" and every package in MSG_DEP_SET to
-## find_package(catkin REQUIRED COMPONENTS ...)
-## * add "message_runtime" and every package in MSG_DEP_SET to
-## catkin_package(CATKIN_DEPENDS ...)
-## * uncomment the add_*_files sections below as needed
-## and list every .msg/.srv/.action file to be processed
-## * uncomment the generate_messages entry below
-## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
-
-## Generate messages in the 'msg' folder
-# add_message_files(
-# FILES
-# Message1.msg
-# Message2.msg
-# )
-## Generate services in the 'srv' folder
- add_service_files(
- FILES
- rail_ical_run.srv
- )
-
-
-## Generate actions in the 'action' folder
-# add_action_files(
-# FILES
-# Action1.action
-# Action2.action
-# )
-
-## Generate added messages and services with any dependencies listed here
- generate_messages(
- DEPENDENCIES
- std_msgs
- geometry_msgs
- )
-set(CMAKE_CXX_FLAGS ${CMAKE_CSS_FLAGS} "-fPIC")
-
-###################################
-## catkin specific configuration ##
-###################################
-## The catkin_package macro generates cmake config files for your package
-## Declare things to be passed to dependent projects
-## INCLUDE_DIRS: uncomment this if you package contains header files
-## 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
+generate_messages(
+ DEPENDENCIES
+ geometry_msgs
+ std_msgs
+)
+
+
catkin_package(
-# LIBRARIES intrinsic_cal
- CATKIN_DEPENDS roscpp rospy std_msgs geometry_msgs
-# DEPENDS system_lib
+ CATKIN_DEPENDS
+ geometry_msgs
+ industrial_extrinsic_cal
+ message_runtime
+ rosconsole
+ roscpp
+ roslib
+ std_msgs
+ std_srvs
+ DEPENDS
+ CERES
)
-###########
-## Build ##
-###########
-## Specify additional locations of header files
-## Your package locations should be listed before other locations
-# include_directories(include)
include_directories(
- ${catkin_INCLUDE_DIRS} ${CERES_INCLUDE_DIRS}
+ ${catkin_INCLUDE_DIRS}
+ ${CERES_INCLUDE_DIRS}
)
-## Declare a cpp library
-# add_library(intrinsic_cal
-# src/${PROJECT_NAME}/intrinsic_cal.cpp
-# )
-## Declare a cpp executable
-#add_executable(create_ical_scenes src/create_ical_scenes.cpp)
add_executable(rail_ical src/rail_cal.cpp)
-add_dependencies( rail_ical ${PROJECT_NAME}_generate_messages_cpp)
-target_link_libraries(rail_ical industrial_extrinsic_cal ${catkin_LIBRARIES} )
-
-## Add cmake target dependencies of the executable/library
-## as an example, message headers may need to be generated before nodes
-# add_dependencies(intrinsic_cal_node intrinsic_cal_generate_messages_cpp)
-#add_dependencies(create_ical_scenes ${catkin_EXPORTED_TARGETS})
-## Specify libraries to link a library or executable target against
-# target_link_libraries(intrinsic_cal_node
-# ${catkin_LIBRARIES}
-# )
-#target_link_libraries(create_ical_scenes ${catkin_LIBRARIES} )
-target_link_libraries(rail_ical ${catkin_LIBRARIES} )
-
-#############
-## Install ##
-#############
-
-# all install targets should use catkin DESTINATION variables
-# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
-
-## Mark executable scripts (Python etc.) for installation
-## in contrast to setup.py, you can choose the destination
-# install(PROGRAMS
-# scripts/my_python_script
-# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-# )
-
-## Mark executables and/or libraries for installation
-# install(TARGETS intrinsic_cal intrinsic_cal_node
-# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
-# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
-# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-# )
-
-## Mark cpp header files for installation
-# install(DIRECTORY include/${PROJECT_NAME}/
-# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
-# FILES_MATCHING PATTERN "*.h"
-# PATTERN ".svn" EXCLUDE
-# )
-
-## Mark other files for installation (e.g. launch and bag files, etc.)
-# install(FILES
-# # myfile1
-# # myfile2
-# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
-# )
-
-#############
-## Testing ##
-#############
-
-## Add gtest based cpp test target and link libraries
-# catkin_add_gtest(${PROJECT_NAME}-test test/test_intrinsic_cal.cpp)
-# if(TARGET ${PROJECT_NAME}-test)
-# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
-# endif()
-
-## Add folders to be run by python nosetests
-# catkin_add_nosetests(test)
+add_dependencies(rail_ical ${PROJECT_NAME}_generate_messages_cpp)
+target_link_libraries(rail_ical ${catkin_LIBRARIES} ${CERES_LIBRARIES})
+
+
+install(
+ TARGETS
+ rail_ical
+ RUNTIME DESTINATION
+ ${CATKIN_PACKAGE_BIN_DESTINATION}
+)
+
+install(
+ DIRECTORY
+ launch
+ DESTINATION
+ ${CATKIN_PACKAGE_SHARE_DESTINATION}
+)
+
+install(
+ FILES
+ asus_ir_cal.rviz
+ DESTINATION
+ ${CATKIN_PACKAGE_SHARE_DESTINATION}
+)
diff --git a/intrinsic_cal/package.xml b/intrinsic_cal/package.xml
index c214b53f..0b8ea962 100644
--- a/intrinsic_cal/package.xml
+++ b/intrinsic_cal/package.xml
@@ -1,68 +1,38 @@
intrinsic_cal
- 0.0.0
- The intrinsic_cal package
+ 0.1.0
+
+ Intrinsic calibration.
+
+ Chris Lewis
+ Chris Lewis
+ Apache2.0
+
+ http://wiki.ros.org/intrinsic_cal
+ https://github.com/ros-industrial/industrial_calibration/issues
+ https://github.com/ros-industrial/industrial_calibration
-
-
-
- clewis
-
-
-
-
-
- Apache
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
catkin
+
+ geometry_msgs
industrial_extrinsic_cal
+ message_generation
+ rosconsole
roscpp
- rospy
+ roslib
std_msgs
- std_srvs
- roslib
- genmsg
- geometry_msgs
+ std_srvs
+
+ geometry_msgs
+ image_view
industrial_extrinsic_cal
+ message_runtime
+ nodelet
+ rosconsole
roscpp
- rospy
+ roslib
+ rviz
std_msgs
- std_srvs
- roslib
- genmsg
- geometry_msgs
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
+ std_srvs
+
diff --git a/rgbd_depth_correction/CMakeLists.txt b/rgbd_depth_correction/CMakeLists.txt
index d1e38628..c2fc1a3c 100644
--- a/rgbd_depth_correction/CMakeLists.txt
+++ b/rgbd_depth_correction/CMakeLists.txt
@@ -1,138 +1,117 @@
cmake_minimum_required(VERSION 2.8.3)
project(rgbd_depth_correction)
-## Find catkin macros and libraries
-## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
-## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
+ cv_bridge
+ geometry_msgs
+ industrial_extrinsic_cal
+ message_filters
+ nodelet
pcl_conversions
pcl_msgs
pcl_ros
+ pluginlib
roscpp
- message_generation
sensor_msgs
+ std_srvs
+ target_finder
tf
- geometry_msgs
tf2_bullet
- rospy
- target_finder
tf_conversions
- nodelet
- cv_bridge
- industrial_extrinsic_cal
)
-## System dependencies are found with CMake's conventions
-# find_package(Boost REQUIRED COMPONENTS system)
+
find_package(Boost REQUIRED COMPONENTS thread)
-# Ceres
-FIND_PACKAGE(Ceres REQUIRED)
-IF (CERES_FOUND)
- MESSAGE("-- Found Ceres version ${CERES_VERSION}: ${CERES_INCLUDE_DIRS}")
-ENDIF (CERES_FOUND)
-
-## Uncomment this if the package has a setup.py. This macro ensures
-## modules and global scripts declared therein get installed
-## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
-# catkin_python_setup()
-
-################################################
-## Declare ROS messages, services and actions ##
-################################################
-
-## To declare and build messages, services or actions from within this
-## package, follow these steps:
-## * Let MSG_DEP_SET be the set of packages whose message types you use in
-## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
-## * In the file package.xml:
-## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
-## * If MSG_DEP_SET isn't empty the following dependencies might have been
-## pulled in transitively but can be declared for certainty nonetheless:
-## * add a build_depend tag for "message_generation"
-## * add a run_depend tag for "message_runtime"
-## * In this file (CMakeLists.txt):
-## * add "message_generation" and every package in MSG_DEP_SET to
-## find_package(catkin REQUIRED COMPONENTS ...)
-## * add "message_runtime" and every package in MSG_DEP_SET to
-## catkin_package(CATKIN_DEPENDS ...)
-## * uncomment the add_*_files sections below as needed
-## and list every .msg/.srv/.action file to be processed
-## * uncomment the generate_messages entry below
-## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
-
-## Generate messages in the 'msg' folder
-# add_message_files(
-# FILES
-# Message1.msg
-# Message2.msg
-# )
-
-## Generate services in the 'srv' folder
-#add_service_files( FILES)
-
-## Generate actions in the 'action' folder
-# add_action_files(
-# FILES
-# Action1.action
-# Action2.action
-# )
-
-## Generate added messages and services with any dependencies listed here
-# generate_messages(
-# DEPENDENCIES
-# pcl_msgs# sensor_msgs# visualization_msgs
-# )
-#generate_messages(DEPENDENCIES geometry_msgs sensor_msgs)
-
-
-# macro definitions required by simple_message library
-add_definitions(-DROS=1) #build using ROS libraries
-#add_definitions(-DLINUXSOCKETS=1) #use linux sockets for communication
-
-###################################
-## catkin specific configuration ##
-###################################
-## The catkin_package macro generates cmake config files for your package
-## Declare things to be passed to dependent projects
-## INCLUDE_DIRS: uncomment this if you package contains header files
-## 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(Ceres REQUIRED)
+message("-- Found Ceres version ${CERES_VERSION}: ${CERES_INCLUDE_DIRS}")
+
+find_package(PkgConfig REQUIRED)
+pkg_check_modules(yaml_cpp REQUIRED yaml-cpp)
+if(NOT ${yaml_cpp_VERSION} VERSION_LESS "0.5")
+ add_definitions(-DHAVE_NEW_YAMLCPP)
+endif()
+
+# resolve include path
+find_path(
+ yaml_cpp_INCLUDE_DIR
+ # bit of a trick
+ NAMES yaml-cpp/yaml.h
+ PATHS ${yaml_cpp_INCLUDE_DIRS}
+)
+
+# determine absolute path to library
+find_library(
+ yaml_cpp_LIBRARY
+ NAMES ${yaml_cpp_LIBRARIES}
+ PATHS ${yaml_cpp_LIBRARY_DIRS}
+)
+
+#message("yaml_cpp_INCLUDE_DIRS: ${yaml_cpp_INCLUDE_DIRS}")
+#message("yaml_cpp_INCLUDE_DIR: ${yaml_cpp_INCLUDE_DIR}")
+#message("yaml_cpp_LIBRARY: ${yaml_cpp_LIBRARY}")
+
+
catkin_package(
- INCLUDE_DIRS include
- LIBRARIES depth_calibration
- CATKIN_DEPENDS message_runtime pcl_conversions pcl_msgs pcl_ros roscpp sensor_msgs
- tf geometry_msgs nodelet
- #DEPENDS system_lib
+ CATKIN_DEPENDS
+ cv_bridge
+ geometry_msgs
+ industrial_extrinsic_cal
+ message_filters
+ nodelet
+ pcl_conversions
+ pcl_msgs
+ pcl_ros
+ pluginlib
+ roscpp
+ sensor_msgs
+ std_srvs
+ target_finder
+ tf
+ tf2_bullet
+ tf_conversions
+ DEPENDS
+ Boost
+ CERES
)
-###########
-## Build ##
-###########
-## Specify additional locations of header files
-## Your package locations should be listed before other locations
-# include_directories(include)
include_directories(
include
${catkin_INCLUDE_DIRS}
${CERES_INCLUDE_DIRS}
+ ${yaml_cpp_INCLUDE_DIR}
)
-add_library(rgbd_depth_correction
- src/depth_correction.cpp
-)
-target_link_libraries(rgbd_depth_correction ${catkin_LIBRARIES} ${CERES_LIBRARIES} yaml-cpp)
-add_dependencies(rgbd_depth_correction ${PROJECT_NAME}_generate_messages_cpp)
+add_library(rgbd_depth_correction src/depth_correction.cpp)
+target_link_libraries(rgbd_depth_correction ${catkin_LIBRARIES} ${yaml_cpp_LIBRARY} ${CERES_LIBRARIES})
+add_dependencies(rgbd_depth_correction ${catkin_EXPORTED_TARGETS})
add_executable(depth_calibration src/depth_calibration.cpp)
-
-target_link_libraries(depth_calibration ${catkin_LIBRARIES} ${CERES_LIBRARIES} yaml-cpp)
-
-add_dependencies(depth_calibration ${PROJECT_NAME}_generate_messages_cpp)
+target_link_libraries(depth_calibration ${catkin_LIBRARIES} ${yaml_cpp_LIBRARY} ${CERES_LIBRARIES})
+add_dependencies(depth_calibration ${catkin_EXPORTED_TARGETS})
+install(
+ TARGETS
+ depth_calibration
+ rgbd_depth_correction
+ ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+ LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+ RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+)
+install(
+ FILES
+ nodelets.xml
+ DESTINATION
+ ${CATKIN_PACKAGE_SHARE_DESTINATION}
+)
+install(
+ DIRECTORY
+ config launch urdf yaml
+ DESTINATION
+ ${CATKIN_PACKAGE_SHARE_DESTINATION}
+)
diff --git a/rgbd_depth_correction/package.xml b/rgbd_depth_correction/package.xml
index 4ba2529f..308d7700 100644
--- a/rgbd_depth_correction/package.xml
+++ b/rgbd_depth_correction/package.xml
@@ -1,51 +1,66 @@
rgbd_depth_correction
- 0.0.0
- RGBD depth calibration and correction
-
- Alex K. Goins
- Apache
-
-
-
+ 0.1.0
+
+ RGBD depth calibration and correction.
+
Alex K. Goins
+ Alex K. Goins
+ Apache2.0
- message_generation
- message_runtime
+ http://wiki.ros.org/rgbd_depth_correction
+ https://github.com/ros-industrial/industrial_calibration/issues
+ https://github.com/ros-industrial/industrial_calibration
catkin
pkg-config
+
+ boost
+ cv_bridge
+ geometry_msgs
+ industrial_extrinsic_cal
+ message_filters
+ nodelet
pcl_conversions
pcl_msgs
pcl_ros
+ pluginlib
roscpp
sensor_msgs
- tf
- geometry_msgs
+ std_srvs
+ target_finder
tf2_bullet
- rospy
+ tf
tf_conversions
- nodelet
target_finder
- cv_bridge
+ yaml-cpp
+ boost
cv_bridge
- target_finder
- tf_conversions
+ geometry_msgs
+ image_view
+ industrial_extrinsic_cal
+ joint_state_publisher
+ message_filters
+ nodelet
+ openni2_launch
pcl_conversions
pcl_msgs
pcl_ros
+ pluginlib
+ robot_state_publisher
roscpp
+ rviz
sensor_msgs
- tf
- geometry_msgs
+ std_srvs
+ target_finder
tf2_bullet
- rospy
- nodelet
+ tf
+ tf_conversions
+ yaml-cpp
-
diff --git a/target_finder/CMakeLists.txt b/target_finder/CMakeLists.txt
index 22034779..40c9c4b5 100644
--- a/target_finder/CMakeLists.txt
+++ b/target_finder/CMakeLists.txt
@@ -1,203 +1,90 @@
cmake_minimum_required(VERSION 2.8.3)
project(target_finder)
-## Find catkin macros and libraries
-## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
-## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
+ geometry_msgs
industrial_extrinsic_cal
- roscpp
- rospy
+ message_generation
rosconsole
- std_msgs
- cv_bridge
- tf
- std_srvs
- roslib
- geometry_msgs
+ roscpp
+ roslib
sensor_msgs
+ std_msgs
+ std_srvs
+ tf
+)
+
+
+#set(CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} "-fPIC")
+
+find_package(Boost REQUIRED)
+
+find_package(Ceres REQUIRED)
+message("-- Found Ceres version ${CERES_VERSION}: ${CERES_INCLUDE_DIRS}")
+
+
+add_service_files(
+ FILES
+ target_locater.srv
)
-set(CMAKE_CXX_FLAGS ${CMAKE_CSS_FLAGS} "-fPIC")
-
-# Opencv
-FIND_PACKAGE(OpenCV REQUIRED)
-IF (OPENCV_FOUND)
- MESSAGE("-- Found OpenCV version ${OPENCV_VERSION}: ${OPENCV_INCLUDE_DIRS}")
-ENDIF (OPENCV_FOUND)
-
-# Ceres
-FIND_PACKAGE(Ceres REQUIRED)
-IF (CERES_FOUND)
- MESSAGE("-- Found Ceres version ${CERES_VERSION}: ${CERES_INCLUDE_DIRS}")
-ENDIF (CERES_FOUND)
-
-# Eigen
-#FIND_PACKAGE(Eigen REQUIRED)
-#IF (EIGEN_FOUND)
-# MESSAGE("-- Found Eigen version ${EIGEN_VERSION}: ${EIGEN_INCLUDE_DIRS}")
-#ENDIF (EIGEN_FOUND)
-
-## System dependencies are found with CMake's conventions
-# find_package(Boost REQUIRED COMPONENTS system)
-
-
-## Uncomment this if the package has a setup.py. This macro ensures
-## modules and global scripts declared therein get installed
-## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
-# catkin_python_setup()
-
-################################################
-## Declare ROS messages, services and actions ##
-################################################
-
-## To declare and build messages, services or actions from within this
-## package, follow these steps:
-## * Let MSG_DEP_SET be the set of packages whose message types you use in
-## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
-## * In the file package.xml:
-## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
-## * If MSG_DEP_SET isn't empty the following dependencies might have been
-## pulled in transitively but can be declared for certainty nonetheless:
-## * add a build_depend tag for "message_generation"
-## * add a run_depend tag for "message_runtime"
-## * In this file (CMakeLists.txt):
-## * add "message_generation" and every package in MSG_DEP_SET to
-## find_package(catkin REQUIRED COMPONENTS ...)
-## * add "message_runtime" and every package in MSG_DEP_SET to
-## catkin_package(CATKIN_DEPENDS ...)
-## * uncomment the add_*_files sections below as needed
-## and list every .msg/.srv/.action file to be processed
-## * uncomment the generate_messages entry below
-## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
-
-## Generate messages in the 'msg' folder
-# add_message_files(
-# FILES
-# Message1.msg
-# Message2.msg
-# )
-
-## Generate services in the 'srv' folder
- add_service_files(
- FILES
- target_locater.srv
- )
-
-## Generate actions in the 'action' folder
-# add_action_files(
-# FILES
-# Action1.action
-# Action2.action
-# )
-
-## Generate added messages and services with any dependencies listed here
generate_messages(
- DEPENDENCIES
- std_msgs
- geometry_msgs
+ DEPENDENCIES
+ geometry_msgs
sensor_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
-## INCLUDE_DIRS: uncomment this if you package contains header files
-## 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(
- INCLUDE_DIRS include
-# LIBRARIES
- CATKIN_DEPENDS roscpp std_msgs rosconsole std_srvs roslib
-# DEPENDS
+ CATKIN_DEPENDS
+ geometry_msgs
+ industrial_extrinsic_cal
+ message_runtime
+ rosconsole
+ roscpp
+ roslib
+ sensor_msgs
+ std_msgs
+ std_srvs
+ tf
+ DEPENDS
+ Boost
+ CERES
)
-###########
-## Build ##
-###########
-## Specify additional locations of header files
-## Your package locations should be listed before other locations
-# include_directories(include)
include_directories(
-# ${catkin_INCLUDE_DIRS} ${EIGEN_INCLUDE_DIRS} ${CERES_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS}
- ${catkin_INCLUDE_DIRS} ${CERES_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS}
+ include
+ ${catkin_INCLUDE_DIRS}
+ ${CERES_INCLUDE_DIRS}
)
-## Declare a cpp library
-# add_library(target_finder
-# src/${PROJECT_NAME}/target_finder.cpp
-# )
-## Declare a cpp executable
add_executable(target_gen src/nodes/grid_generator.cpp)
add_executable(call_service src/nodes/call_service.cpp)
add_executable(target_locator_srv src/nodes/target_locator.cpp)
+add_dependencies(call_service ${catkin_EXPORTED_TARGETS} ${target_finder_EXPORTED_TARGETS})
+add_dependencies(target_locator_srv ${catkin_EXPORTED_TARGETS} ${target_finder_EXPORTED_TARGETS})
+
+target_link_libraries(target_gen ${catkin_LIBRARIES})
+target_link_libraries(call_service ${catkin_LIBRARIES})
+target_link_libraries(target_locator_srv ${catkin_LIBRARIES} ${CERES_LIBRARIES})
-## Add cmake target dependencies of the executable/library
-## as an example, message headers may need to be generated before nodes
-# add_dependencies(target_finder_node target_finder_generate_messages_cpp)
-add_dependencies(call_service ${PROJECT_NAME}_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-add_dependencies(target_locator_srv ${PROJECT_NAME}_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
-
-## Specify libraries to link a library or executable target against
-# target_link_libraries(target_finder_node
-# ${catkin_LIBRARIES}
-# )
-target_link_libraries(target_gen ${catkin_LIBRARIES} )
-target_link_libraries(call_service industrial_extrinsic_cal ${catkin_LIBRARIES} )
-target_link_libraries(target_locator_srv industrial_extrinsic_cal ${catkin_LIBRARIES} ${CERES_LIBRARIES} )
-
-
-#############
-## Install ##
-#############
-
-# all install targets should use catkin DESTINATION variables
-# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
-
-## Mark executable scripts (Python etc.) for installation
-## in contrast to setup.py, you can choose the destination
-# install(PROGRAMS
-# scripts/my_python_script
-# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-# )
-
-## Mark executables and/or libraries for installation
-# install(TARGETS target_finder target_finder_node
-# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
-# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
-# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
-# )
-
-## Mark cpp header files for installation
-# install(DIRECTORY include/${PROJECT_NAME}/
-# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
-# FILES_MATCHING PATTERN "*.h"
-# PATTERN ".svn" EXCLUDE
-# )
-
-## Mark other files for installation (e.g. launch and bag files, etc.)
-# install(FILES
-# # myfile1
-# # myfile2
-# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
-# )
-
-#############
-## Testing ##
-#############
-
-## Add gtest based cpp test target and link libraries
-# catkin_add_gtest(${PROJECT_NAME}-test test/test_target_finder.cpp)
-# if(TARGET ${PROJECT_NAME}-test)
-# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
-# endif()
-
-## Add folders to be run by python nosetests
-# catkin_add_nosetests(test)
+
+install(
+ TARGETS
+ call_service
+ target_gen
+ target_locator_srv
+ RUNTIME DESTINATION
+ ${CATKIN_PACKAGE_BIN_DESTINATION}
+)
+
+install(
+ DIRECTORY
+ config launch
+ DESTINATION
+ ${CATKIN_PACKAGE_SHARE_DESTINATION}
+)
diff --git a/target_finder/package.xml b/target_finder/package.xml
index e99eae81..364d837d 100644
--- a/target_finder/package.xml
+++ b/target_finder/package.xml
@@ -1,75 +1,43 @@
target_finder
- 0.0.0
- The target_finder package
+ 0.1.0
+
+ The target finder.
+
+ Chris Lewis
+ Chris Lewis
+ Apache2.0
+
+ http://wiki.ros.org/target_finder
+ https://github.com/ros-industrial/industrial_calibration/issues
+ https://github.com/ros-industrial/industrial_calibration
-
-
-
- clewis
-
-
-
-
-
- Apache
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
catkin
+
+ boost
+ geometry_msgs
industrial_extrinsic_cal
- roscpp
- rospy
+ message_generation
rosconsole
- std_msgs
- cv_bridge
- tf
- std_srvs
+ roscpp
roslib
- geometry_msgs
sensor_msgs
+ std_msgs
+ std_srvs
+ tf
+
+ geometry_msgs
+ image_view
industrial_extrinsic_cal
- roscpp
- rospy
+ message_runtime
+ nodelet
rosconsole
- std_msgs
- cv_bridge
- tf
- std_srvs
+ roscpp
roslib
- geometry_msgs
+ rviz
sensor_msgs
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
+ std_msgs
+ std_srvs
+ tf
+