Skip to content

Commit

Permalink
Addressed issue with Eigen dependency and missing install commands on…
Browse files Browse the repository at this point in the history
… CMakeLists.txt files
  • Loading branch information
jrgnicho authored and Levi-Armstrong committed May 5, 2017
1 parent 8974f5f commit e3433b1
Show file tree
Hide file tree
Showing 54 changed files with 295 additions and 153 deletions.
24 changes: 24 additions & 0 deletions .travis.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
sudo: required
dist: trusty
language: generic
compiler:
- gcc
notifications:
email:
recipients:
- jrgnichodevel@gmail.com
- levi.armstrong@gmail.com
on_failure: always

env:
matrix:
- USE_DEB=true
ROS_DISTRO="indigo"
ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu
- USE_DEB=true
ROS_DISTRO="indigo"
ROS_REPOSITORY_PATH=http://packages.ros.org/ros-shadow-fixed/ubuntu
install:
- git clone https://github.com/ros-industrial/industrial_ci.git .ci_config
script:
- source .ci_config/travis.sh
21 changes: 12 additions & 9 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,17 +5,19 @@
- Build the workspace:
- Cd into the catkin workspace directory and type the following command:
```
catkin_make --jobs=4
catkin build
```

#### Unit Test
- Run stomp_core Unit Test:
- Run all of industrial_moveit unit tests:
- Cd into the catkin workspace directory and type the following command:
```
catkin_make run_tests_stomp_core_gtest
catkin run_tests
```
- Run the stomp_core unit tests:
```
catkin run_tests stomp_core
```
- Inspect the Unit test
- *roscd* into the **stomp_core** package and go locate the "stomp_3dof.cpp" file inside the **test** directory.


#### Stomp Moveit Demo
Expand All @@ -34,8 +36,9 @@ catkin_make run_tests_stomp_core_gtest
- **roscd** into the **stomp_test_kr210_moveit_config** package and locate the "stomp_config.yaml" file under the config directory
- Rerun demo.launch file and plan once again to see how the changes affect the planner's behavior.

==============================================================================================
[ROS-Industrial][] move it meta-package. See the [ROS wiki][] page for more information.
[ROS-Industrial]: http://www.ros.org/wiki/Industrial
[ROS wiki]: http://ros.org/wiki/industrial_moveit
========================================================================
[ROS-Industrial]: http://www.ros.org/wiki/Industrial
[ROS wiki]: http://ros.org/wiki/industrial_moveit
[ConstrainedIK]: http://wiki.ros.org/constrained_ik?distro=indigo
[Stomp MoveIt!]: http://wiki.ros.org/stomp_moveit

11 changes: 11 additions & 0 deletions constrained_ik/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package constrained_ik
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.1.1 (2017-03-24)
------------------

0.1.0 (2017-03-14)
------------------
* Initial release
* Contributors: Jeremy Zoss, Levi Armstrong, Jonathan W Meyer, Dan Solomon
85 changes: 29 additions & 56 deletions constrained_ik/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,37 +27,33 @@ find_package(catkin REQUIRED COMPONENTS
## System dependencies are found with CMake's conventions
find_package(orocos_kdl REQUIRED)
find_package(Boost REQUIRED)
find_package(Eigen REQUIRED)

# We don't build anything here, but in order to export the right
# build flags in catkin_package(), we still have to find Eigen3 here. Note
# that this is somewhat complicated because of our need to support Ubuntu
# all the way back to saucy. First we look for the Eigen3 cmake module
# provided by the libeigen3-dev on newer Ubuntu. If that fails, then we
# fall-back to the version provided by cmake_modules, which is a stand-in.
find_package(Eigen3 QUIET)
if(NOT EIGEN3_FOUND)
# saucy does not have Eigen3, but have Eigen instead
find_package(cmake_modules REQUIRED)
find_package(Eigen REQUIRED)
set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS})
endif()

# Note that eigen 3.2 (on Ubuntu Wily) only provides EIGEN3_INCLUDE_DIR,
# not EIGEN3_INCLUDE_DIRS, so we have to set the latter from the former.
if(NOT EIGEN3_INCLUDE_DIRS)
set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR})
endif()

#add dynamic reconfigure api
generate_dynamic_reconfigure_options(
cfg/CLIKDynamic.cfg
cfg/CLIKPlannerDynamic.cfg
)

#######################################
## 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 # Or other packages containing msgs
# )

###################################
## catkin specific configuration ##
Expand All @@ -68,7 +64,7 @@ generate_dynamic_reconfigure_options(
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include ${catkin_INCLUDE_DIRS}
INCLUDE_DIRS include ${catkin_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS}
LIBRARIES constrained_ik constrained_ik_constraints moveit_clik_planner_plugin constrained_ik_plugin
CATKIN_DEPENDS roscpp urdf eigen_conversions tf_conversions urdf moveit_ros_planning moveit_core dynamic_reconfigure kdl_parser cmake_modules industrial_collision_detection
DEPENDS boost eigen orocos_kdl
Expand All @@ -80,7 +76,7 @@ catkin_package(

## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} ${EIGEN_INCLUDE_DIRS})
include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS})

## Declare a cpp library
add_library(constrained_ik
Expand Down Expand Up @@ -125,33 +121,12 @@ add_library(moveit_clik_planner_plugin

target_link_libraries(moveit_clik_planner_plugin constrained_ik constrained_ik_constraints ${catkin_LIBRARIES})

## Declare a cpp executable
# add_executable(constrained_ik_node src/constrained_ik_node.cpp)

## Add cmake target dependencies of the executable/library
## as an example, message headers may need to be generated before nodes
# add_dependencies(constrained_ik_node constrained_ik_generate_messages_cpp)

#############
## 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 constrained_ik constrained_ik_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
install(TARGETS constrained_ik LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
install(TARGETS constrained_ik_constraints LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})

## Mark cpp header files for installation
install(DIRECTORY include/${PROJECT_NAME}/
Expand All @@ -169,13 +144,11 @@ install(
${CATKIN_PACKAGE_SHARE_DESTINATION}
)


## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
install(TARGETS constrained_ik_plugin moveit_clik_planner_plugin
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

#############
## Testing ##
Expand Down
10 changes: 5 additions & 5 deletions constrained_ik/package.xml
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
<?xml version="1.0"?>
<package>
<name>constrained_ik</name>
<version>0.0.0</version>
<version>0.1.1</version>
<description>Constraint-based IK solver. Good for high-DOF robots or underconstrained tasks.</description>

<author email="cl__is@swri.org">Chris Lewis</author>
<author email="jz__s@swri.org">Jeremy Zoss</author>
<author email="dps____on@gmail.com">Dan Solomon</author>
<author email="clewis@swri.org">Chris Lewis</author>
<author email="jzoss@swri.org">Jeremy Zoss</author>
<author email="dpsolomon@gmail.com">Dan Solomon</author>
<maintainer email="levi.armstrong@gmail.com">Levi Armstrong</maintainer>
<maintainer email="jzoss@swri.org">Jeremy Zoss, SwRI</maintainer>
<maintainer email="dpsolomon@gmail.com">Dan Solomon, SwRI</maintainer>
<license>Apache 2.0</license>
<url type="website">http://ros.org/wiki/constrained_ik</url>

Expand Down
2 changes: 1 addition & 1 deletion doxygen.config
Original file line number Diff line number Diff line change
Expand Up @@ -743,7 +743,7 @@ WARN_LOGFILE =
# spaces.
# Note: If this tag is empty the current directory is searched.

INPUT = constrained_ik
INPUT = constrained_ik stomp_core stomp_moveit stomp_plugins

# This tag can be used to specify the character encoding of the source files
# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses
Expand Down
11 changes: 11 additions & 0 deletions industrial_collision_detection/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package industrial_collision_detection
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.1.1 (2017-03-24)
------------------

0.1.0 (2017-03-14)
------------------
* Initial release
* Contributors: Levi H Armstrong, Jorge Nicho
10 changes: 5 additions & 5 deletions industrial_collision_detection/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -60,11 +60,11 @@ add_library(${PROJECT_NAME}_plugin
)
target_link_libraries(${PROJECT_NAME}_plugin ${PROJECT_NAME} ${catkin_LIBRARIES})

install(TARGETS ${PROJECT_NAME}
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib)
install(DIRECTORY include/
DESTINATION include)
#############
## Install ##
#############
install(TARGETS ${PROJECT_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})
install(
FILES
industrial_collision_detection_plugin_description.xml
Expand Down
2 changes: 1 addition & 1 deletion industrial_collision_detection/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package>
<name>industrial_collision_detection</name>
<version>0.1.0</version>
<version>0.1.1</version>
<description>The industrial_collision_detection package</description>

<maintainer email="levi.armstrong@swri.org">Levi Armstrong</maintainer>
Expand Down
11 changes: 11 additions & 0 deletions industrial_moveit/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package industrial_moveit
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.1.1 (2017-03-24)
------------------

0.1.0 (2017-03-14)
------------------
* Initial release
* Contributors: Shaun Edwards, Dan Solomon
23 changes: 18 additions & 5 deletions industrial_moveit/package.xml
Original file line number Diff line number Diff line change
@@ -1,11 +1,18 @@
<package>
<name>industrial_moveit</name>
<version>0.0.0</version>
<version>0.1.1</version>
<description>ROS Industrial MoveIt packages.</description>
<author email="jz__s@swri.org">Jeremy Zoss</author>
<author email="dps____on@gmail.com">Dan Solomon</author>
<maintainer email="jzoss@swri.org">Jeremy Zoss</maintainer>
<maintainer email="dpsolomon@gmail.com">Dan Solomon</maintainer>
<author email="clewis@swri.org">Chris Lewis</author>
<author email="dpsolomon@gmail.com">Dan Solomon</author>
<author email="jzoss@swri.org">Jeremy Zoss</author>
<author email="levi.armstrong@gmail.com">Levi Armstrong</author>
<author email="jrgnichodevel@gmail.com">Jorge Nicho</author>
<author email="jonathan.meyer@swri.org">Jonathan Meyer</author>

<maintainer email="levi.armstrong@gmail.com">Levi Armstrong</maintainer>
<maintainer email="jrgnichodevel@gmail.com">Jorge Nicho</maintainer>
<maintainer email="jonathan.meyer@swri.org">Jonathan Meyer</maintainer>

<license>Apache 2.0</license>

<url type="website">http://ros.org/wiki/industrial_moveit</url>
Expand All @@ -15,6 +22,12 @@
<buildtool_depend>catkin</buildtool_depend>

<run_depend>constrained_ik</run_depend>
<run_depend>stomp_core</run_depend>
<run_depend>stomp_moveit</run_depend>
<run_depend>stomp_plugins</run_depend>
<run_depend>industrial_collision_detection</run_depend>
<run_depend>stomp_test_support</run_depend>
<run_depend>stomp_test_kr210_moveit_config</run_depend>

<export>
<metapackage/>
Expand Down
11 changes: 11 additions & 0 deletions industrial_moveit_benchmarking/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package industrial_moveit_benchmarking
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.1.1 (2017-03-24)
------------------

0.1.0 (2017-03-14)
------------------
* Initial release
* Contributors: Jonathan Meyer, Levi Armstrong, Jorge Nicho
2 changes: 1 addition & 1 deletion industrial_moveit_benchmarking/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package>
<name>industrial_moveit_benchmarking</name>
<version>0.1.0</version>
<version>0.1.1</version>
<description>This package contains tools used to benchmark both constrianed_ik and stomp.</description>

<maintainer email="levi.armstrong@gmail.com">Levi Armstrong</maintainer>
Expand Down
11 changes: 11 additions & 0 deletions stomp_core/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package stomp_core
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.1.1 (2017-03-24)
------------------

0.1.0 (2017-03-14)
------------------
* Initial release
* Contributors: Levi H Armstrong, Jorge Nicho
11 changes: 10 additions & 1 deletion stomp_core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ find_package(catkin REQUIRED COMPONENTS
roscpp
cmake_modules
)

find_package(Eigen REQUIRED)

add_definitions("-std=c++11")
Expand All @@ -16,7 +17,7 @@ add_definitions("-std=c++11")
## catkin specific configuration ##
###################################
catkin_package(
INCLUDE_DIRS include
INCLUDE_DIRS include ${EIGEN_INCLUDE_DIRS}
LIBRARIES stomp_core
CATKIN_DEPENDS roscpp cmake_modules
DEPENDS Eigen
Expand Down Expand Up @@ -47,6 +48,14 @@ target_link_libraries(${PROJECT_NAME}_example ${PROJECT_NAME} ${catkin_LIBRARIES
#############
## Install ##
#############
install(TARGETS ${PROJECT_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})

## Mark cpp header files for installation
install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h"
PATTERN ".svn" EXCLUDE
)


#############
Expand Down
Loading

0 comments on commit e3433b1

Please sign in to comment.