Skip to content

Commit

Permalink
Merge pull request RobotLocomotion#1260 from RussTedrake/rdeits-rd-lc…
Browse files Browse the repository at this point in the history
…mtypes-path

Rdeits rd lcmtypes path
  • Loading branch information
RussTedrake committed Aug 16, 2015
2 parents 5d7d230 + 4f1b9a0 commit f551b87
Show file tree
Hide file tree
Showing 12 changed files with 48 additions and 86 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ set(gurobi_GIT_TAG beb0a84a1bcca1eb81a1b87d9fa140f2134d97e9)
set(iris_GIT_REPOSITORY https://github.com/rdeits/iris-distro.git)
set(iris_GIT_TAG 13468e0ea38e72ffae030adaa31e3015ea5f3ce0)
set(lcm_GIT_REPOSITORY https://github.com/RobotLocomotion/lcm-pod.git)
set(lcm_GIT_TAG f072e9a54ae168503de8f9b96a70205d56ff5788) # cmake branch
set(lcm_GIT_TAG 31e9a3e2dd056cac749fc2879e841434181180ad) # cmake branch
set(libbot_GIT_REPOSITORY https://github.com/RobotLocomotion/libbot.git)
set(libbot_GIT_TAG c328b73f3b48008d04468031e26f48468a7e3cc0)
set(mosek_GIT_REPOSITORY https://github.com/RobotLocomotion/mosek.git)
Expand Down
31 changes: 0 additions & 31 deletions drake/lcmtypes/CMakeLists.txt

This file was deleted.

76 changes: 39 additions & 37 deletions drake/solvers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,53 +5,55 @@ pods_find_pkg_config(gurobi)

if (gurobi_FOUND)

add_library(drakeQP QP.cpp)
set_target_properties(drakeQP PROPERTIES COMPILE_FLAGS -fPIC)
pods_use_pkg_config_packages(drakeQP gurobi)

if (MATLAB_FOUND)
add_mex(fastQPmex fastQPmex.cpp)
target_link_libraries(fastQPmex drakeQP)
add_mex(gurobiQPmex gurobiQPmex.cpp)
target_link_libraries(gurobiQPmex drakeQP)
endif()

pods_install_libraries(drakeQP)
pods_install_headers(fastQP.h gurobiQP.h DESTINATION drake)
pods_install_pkg_config_file(drake-qp
LIBS -ldrakeQP
REQUIRES gurobi
VERSION 0.0.1)
add_library(drakeQP QP.cpp)
set_target_properties(drakeQP PROPERTIES COMPILE_FLAGS -fPIC)
pods_use_pkg_config_packages(drakeQP gurobi)

if (MATLAB_FOUND)
add_mex(fastQPmex fastQPmex.cpp)
target_link_libraries(fastQPmex drakeQP)
add_mex(gurobiQPmex gurobiQPmex.cpp)
target_link_libraries(gurobiQPmex drakeQP)
endif()

pods_install_libraries(drakeQP)
pods_install_headers(fastQP.h gurobiQP.h DESTINATION drake)
pods_install_pkg_config_file(drake-qp
LIBS -ldrakeQP
REQUIRES gurobi
VERSION 0.0.1)

endif()

pods_find_pkg_config(snopt_c)

add_mex(lqrmex lqrmex.cpp)
target_link_libraries(lqrmex drakeUtil)
if(MATLAB_FOUND)
add_mex(lqrmex lqrmex.cpp)
target_link_libraries(lqrmex drakeUtil)
endif()

if(snopt_c_FOUND AND MATLAB_FOUND)
add_mex(NonlinearProgramSnoptmex NonlinearProgramSnoptmex.cpp)
add_mex(NonlinearProgramSnoptmex NonlinearProgramSnoptmex.cpp)
pods_use_pkg_config_packages(NonlinearProgramSnoptmex snopt_c)
set_target_properties(NonlinearProgramSnoptmex PROPERTIES COMPILE_FLAGS -fPIC)

# link against matlab's copy of the gfortran library, if possible
find_library(GFORTRAN_LIBRARY NAMES gfortran libgfortran
PATHS "${MATLAB_ROOT}/sys/os/"
PATH_SUFFIXES glnxa64/ maci64/ NO_DEFAULT_PATH )
if (NOT GFORTRAN_LIBRARY)
# the above does not seem work on linux out of the box, because matlab
# symlinks to libgfortran.so.3 but not to libgfortran.so, and cmake isn't
# able to find it with the default CMAKE_FIND_LIBRARY_SUFFIXES. Instead
# of setting that variable, here is the annoying work-around:
find_file(GFORTRAN_LIBRARY NAMES libgfortran.so.3
PATHS "${MATLAB_ROOT}/sys/os/"
PATH_SUFFIXES glnxa64/ maci64/ NO_DEFAULT_PATH)
endif()

if (GFORTRAN_LIBRARY)
target_link_libraries(NonlinearProgramSnoptmex ${GFORTRAN_LIBRARY})
endif()
# link against matlab's copy of the gfortran library, if possible
find_library(GFORTRAN_LIBRARY NAMES gfortran libgfortran
PATHS "${MATLAB_ROOT}/sys/os/"
PATH_SUFFIXES glnxa64/ maci64/ NO_DEFAULT_PATH )
if (NOT GFORTRAN_LIBRARY)
# the above does not seem work on linux out of the box, because matlab
# symlinks to libgfortran.so.3 but not to libgfortran.so, and cmake isn't
# able to find it with the default CMAKE_FIND_LIBRARY_SUFFIXES. Instead
# of setting that variable, here is the annoying work-around:
find_file(GFORTRAN_LIBRARY NAMES libgfortran.so.3
PATHS "${MATLAB_ROOT}/sys/os/"
PATH_SUFFIXES glnxa64/ maci64/ NO_DEFAULT_PATH)
endif()

if (GFORTRAN_LIBRARY)
target_link_libraries(NonlinearProgramSnoptmex ${GFORTRAN_LIBRARY})
endif()
endif()

add_subdirectory(qpSpline)
4 changes: 0 additions & 4 deletions drake/systems/controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,10 +1,6 @@
include_directories(${PROJECT_SOURCE_DIR}/systems/robotInterfaces)
include_directories(${PROJECT_SOURCE_DIR}/util/test)

if (LCM_FOUND)
include_directories (${CMAKE_BINARY_DIR}/lcmgen/lcmtypes )
endif()

add_library(drakeControlUtil SHARED controlUtil.cpp)
pods_find_pkg_config(terrain-map)
if (terrain-map_FOUND)
Expand Down
2 changes: 1 addition & 1 deletion drake/systems/controllers/QPCommon.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include <lcm/lcm-cpp.hpp>
#include "lcmUtil.h"
#include "testUtil.h"
#include "drake/lcmt_zmp_com_observer_state.hpp"
#include "lcmtypes/drake/lcmt_zmp_com_observer_state.hpp"

const bool CHECK_CENTROIDAL_MOMENTUM_RATE_MATCHES_TOTAL_WRENCH = false;
const bool PUBLISH_ZMP_COM_OBSERVER_STATE = true;
Expand Down
2 changes: 1 addition & 1 deletion drake/systems/controllers/QPCommon.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include "controlUtil.h"
#include "drakeUtil.h"
#include "fastQP.h"
#include "drake/lcmt_qp_controller_input.hpp"
#include "lcmtypes/drake/lcmt_qp_controller_input.hpp"
#include "ExponentialPlusPiecewisePolynomial.h"
#include <vector>
#include "ForceTorqueMeasurement.h"
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include <lcm/lcm.h>
#include <bot_lcmgl_client/lcmgl.h>
#include "drake_lcmt_zmp_com_observer_state.h"
#include "lcmtypes/drake_lcmt_zmp_com_observer_state.h"

bot_lcmgl_t* lcmgl;

Expand Down
1 change: 0 additions & 1 deletion drake/systems/robotInterfaces/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@ include_directories (${PROJECT_SOURCE_DIR}/systems/controllers )
include_directories (${PROJECT_SOURCE_DIR}/systems/plants )
include_directories (${PROJECT_SOURCE_DIR}/systems/plants/joints )
include_directories (${PROJECT_SOURCE_DIR}/solvers/qpSpline )
include_directories (${PROJECT_BINARY_DIR}/lcmgen/lcmtypes )
include_directories (${PROJECT_SOURCE_DIR}/examples/Atlas)

add_library(drakeSide SHARED Side.cpp)
Expand Down
2 changes: 1 addition & 1 deletion drake/systems/robotInterfaces/QPLocomotionPlan.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
#include "PiecewisePolynomial.h"
#include "ExponentialPlusPiecewisePolynomial.h"
#include "RigidBodyManipulator.h"
#include "drake/lcmt_qp_controller_input.hpp"
#include "lcmtypes/drake/lcmt_qp_controller_input.hpp"
#include "BodyMotionData.h"
#include "Side.h"
#include <lcm/lcm-cpp.hpp>
Expand Down
3 changes: 0 additions & 3 deletions drake/util/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
include_directories (${PROJECT_BINARY_DIR}/lcmgen/lcmtypes )

if (simulink_FOUND)
add_mex(realtime realtime.cpp)
endif()
Expand Down Expand Up @@ -51,7 +49,6 @@ if (LCM_FOUND)
# note: requires drakeUtil header file, but not linking against it because
# we only need methods that are templated and defined in the header
include_directories (${PROJECT_SOURCE_DIR}/systems/trajectories )
include_directories (${PROJECT_BINARY_DIR}/lcmgen/lcmtypes )
add_library(drakeLCMUtil SHARED lcmUtil.cpp)
add_dependencies(drakeLCMUtil ${LCMTYPES_C_LIBRARY})
target_link_libraries(drakeLCMUtil drakeTrajectories)
Expand Down
8 changes: 4 additions & 4 deletions drake/util/lcmUtil.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@
#include <Eigen/Core>
#include <iostream>
#include "PiecewisePolynomial.h"
#include "drake/lcmt_polynomial.hpp"
#include "drake/lcmt_polynomial_matrix.hpp"
#include "drake/lcmt_piecewise_polynomial.hpp"
#include "drake/lcmt_qp_controller_input.hpp"
#include "lcmtypes/drake/lcmt_polynomial.hpp"
#include "lcmtypes/drake/lcmt_polynomial_matrix.hpp"
#include "lcmtypes/drake/lcmt_piecewise_polynomial.hpp"
#include "lcmtypes/drake/lcmt_qp_controller_input.hpp"

#undef DLLEXPORT
#if defined(WIN32) || defined(WIN64)
Expand Down
1 change: 0 additions & 1 deletion drake/util/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@

include_directories(..)
include_directories(${PROJECT_SOURCE_DIR}/systems/trajectories)
include_directories(${PROJECT_BINARY_DIR}/lcmgen/lcmtypes)

if (NOT WIN32)
# doesn't work because the timing tests require the <chrono> include
Expand Down

0 comments on commit f551b87

Please sign in to comment.