Skip to content

Commit

Permalink
Merge pull request #109 from 130s/i/fix/dependency
Browse files Browse the repository at this point in the history
[indigo] Use ceres binary
  • Loading branch information
drchrislewis authored Sep 22, 2017
2 parents 1069095 + 154a176 commit cc04633
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 3 deletions.
7 changes: 5 additions & 2 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,13 @@ env:
ROS_REPOSITORY_PATH=http://packages.ros.org/ros-shadow-fixed/ubuntu
NOT_TEST_BUILD=true
NOT_TEST_INSTALL=true

- ROS_DISTRO="indigo"
PRERELEASE=true
matrix:
allow_failures:
- env: ROS_DISTRO="indigo" PRERELEASE=true
install:
- git clone https://github.com/ros-industrial/industrial_ci.git .ci_config

script:
- source .travis_ceres.sh
- source .ci_config/travis.sh
5 changes: 4 additions & 1 deletion industrial_extrinsic_cal/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@ find_package(Boost REQUIRED)
find_package(Ceres REQUIRED)
message("-- Found Ceres version ${CERES_VERSION}: ${CERES_INCLUDE_DIRS}")

find_package(Eigen3 REQUIRED)

find_package(OpenCV 2 REQUIRED)
message("-- Found OpenCV version ${OpenCV_VERSION}: ${OpenCV_INCLUDE_DIRS}")

Expand Down Expand Up @@ -108,6 +110,7 @@ catkin_package(
DEPENDS
Boost
CERES
EIGEN3
)


Expand All @@ -116,11 +119,11 @@ include_directories(
include
${catkin_INCLUDE_DIRS}
${CERES_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${yaml_cpp_INCLUDE_DIR}
)


# target: main library
add_library(
industrial_extrinsic_cal
Expand Down
6 changes: 6 additions & 0 deletions industrial_extrinsic_cal/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,10 @@
<build_depend>actionlib_msgs</build_depend>
<build_depend>boost</build_depend>
<build_depend>cv_bridge</build_depend>
<build_depend>eigen</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>image_transport</build_depend>
<build_depend>libceres-dev</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>moveit_ros_planning_interface</build_depend>
<build_depend>rosconsole</build_depend>
Expand All @@ -31,16 +33,19 @@
<build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>std_srvs</build_depend>
<build_depend>suitesparse</build_depend>
<build_depend>tf</build_depend>
<build_depend>tf_conversions</build_depend>
<build_depend>yaml-cpp</build_depend>

<run_depend>actionlib</run_depend>
<run_depend>actionlib_msgs</run_depend>
<run_depend>cv_bridge</run_depend>
<run_depend>eigen</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>image_transport</run_depend>
<run_depend>image_view</run_depend>
<run_depend>libceres-dev</run_depend>
<run_depend>message_runtime</run_depend>
<run_depend>motoman_driver</run_depend>
<run_depend>motoman_sia20d_support</run_depend>
Expand All @@ -56,6 +61,7 @@
<run_depend>sensor_msgs</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>std_srvs</run_depend>
<run_depend>suitesparse</run_depend>
<run_depend>tf</run_depend>
<run_depend>tf_conversions</run_depend>
<run_depend>yaml-cpp</run_depend>
Expand Down

0 comments on commit cc04633

Please sign in to comment.