Skip to content

Commit

Permalink
fixed upstream merge conflict
Browse files Browse the repository at this point in the history
  • Loading branch information
psiorx committed Mar 3, 2016
2 parents 717d199 + e8ca6af commit 269db65
Show file tree
Hide file tree
Showing 346 changed files with 98,526 additions and 78,128 deletions.
2 changes: 2 additions & 0 deletions .clang-format
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
---
BasedOnStyle: Google
25 changes: 17 additions & 8 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,22 +34,20 @@ option(REMOVE_UNUSED_EXTERNALS "enable this to remove those projects from disk"
# ON by default:
option(WITH_EIGEN "required c++ matrix library. only disable if you have it already." ON)
option(WITH_SWIGMAKE "helper tools to build python & MATLAB wrappers for C++ libraries with Eigen" ON)
option(WITH_BULLET "used for collision detection" ON)
option(WITH_LCM "interprocess communications protocol for visualizers, etc" ON)
if (WIN32)
if (CMAKE_SIZEOF_VOID_P EQUAL 8) # gtk only compiles on win64 right now
option(WITH_LCM "interprocess communications protocol for visualizers, etc" ON)
option(WITH_GTK "precompiled gtk binaries/headers for Windows" ON) # needed for lcm on windows
endif()
else()
option(WITH_LCM "interprocess communications protocol for visualizers, etc" ON)
option(WITH_DIRECTOR "vtk-based visualization tool and robot user interface" ON) # not win32 yet. it builds on windows, but requires manually installation of vtk, etc. perhaps make a precompiled director pod (a bit like snopt)
option(WITH_LIBBOT "simple open-gl visualizer + lcmgl for director" ON) # there is hope, but i spent a long time cleaning up c/c++ language errors trying to make msvc happy.. and still had a long way to go.
option(WITH_BULLET "used for collision detection" ON) # almost works. just one remaining link error..?
option(WITH_SWIG_MATLAB "A version of SWIG with MATLAB support" ON)
endif()
find_program(matlab matlab)
if (matlab)
option(WITH_SPOTLESS "polynomial optimization front-end for MATLAB" ON)
endif()
option(WITH_YAML_CPP "library for reading and writing yaml configuration files" ON)

option(WITH_SNOPT_PRECOMPILED "precompiled binaries only for snopt; the source requires a license (will be disabled if WITH_SNOPT=ON)" ON)

Expand Down Expand Up @@ -89,7 +87,7 @@ set(libbot_dependencies lcm)
set(director_dependencies lcm libbot)
set(iris_dependencies eigen mosek)
set(signalscope_dependencies director)
set(drake_dependencies cmake eigen lcm libbot bullet octomap snopt gurobi swig_matlab swigmake)
set(drake_dependencies cmake eigen lcm libbot bullet octomap snopt gurobi swig_matlab swigmake yaml_cpp)

# download information, in alphabetical order
set(avl_GIT_REPOSITORY https://github.com/RobotLocomotion/avl.git)
Expand All @@ -99,7 +97,7 @@ set(bertini_GIT_REPOSITORY [email protected]:RobotLocomotion/bertini.git)
set(bertini_GIT_TAG 3ae3e3ad3534acb4b6f7a4c3c22728b493beaa80)
set(bertini_IS_PUBLIC FALSE)
set(bullet_GIT_REPOSITORY https://github.com/RobotLocomotion/bullet-pod.git)
set(bullet_GIT_TAG 4319ffd7e9251066d93064f5a8dab12e33dbe5e2)
set(bullet_GIT_TAG 248df52f24ff149a8df57f3958f739d8cc6f4e57)
set(bullet_IS_PUBLIC TRUE)
set(bullet_IS_CMAKE_POD TRUE)
set(cmake_GIT_REPOSITORY https://github.com/RobotLocomotion/cmake.git)
Expand All @@ -117,7 +115,7 @@ set(eigen_GIT_TAG 20a633e8f0a285edf9dcc5a06cc9e80774920a7f)
set(eigen_IS_CMAKE_POD TRUE)
set(eigen_IS_PUBLIC TRUE)
set(gtk_GIT_REPOSITORY https://github.com/RobotLocomotion/gtk-pod.git)
set(gtk_GIT_TAG 78a110023b527e6ee372e4686118a8c7a6a51131)
set(gtk_GIT_TAG 4730a7d3274a35280f1c2c6337eb182935c87fc2)
set(gtk_IS_CMAKE_POD TRUE)
set(gtk_IS_PUBLIC TRUE)
set(gloptipoly_GIT_REPOSITORY [email protected]:RobotLocomotion/gloptipoly3.git) # todo: rename that repo
Expand Down Expand Up @@ -177,6 +175,15 @@ set(textbook_IS_PUBLIC TRUE)
set(yalmip_GIT_REPOSITORY https://github.com/RobotLocomotion/yalmip.git)
set(yalmip_GIT_TAG c071fb7b7193491f8eefadba3bfff26160ad6cd4)
set(yalmip_IS_PUBLIC TRUE)
set(yaml_cpp_GIT_REPOSITORY https://github.com/jbeder/yaml-cpp.git)
set(yaml_cpp_GIT_TAG 57805dfd6a741e55477ea8d4d5b3b6f0272d1f0e)
set(yaml_cpp_IS_PUBLIC TRUE)
set(yaml_cpp_IS_CMAKE_POD TRUE)
if (APPLE OR WIN32)
set(yaml_cpp_ADDITIONAL_CMAKE_CONFIGURE_ARGS -DBUILD_SHARED_LIBS=OFF)
else()
set(yaml_cpp_ADDITIONAL_CMAKE_CONFIGURE_ARGS -DBUILD_SHARED_LIBS=ON)
endif()
set(xfoil_GIT_REPOSITORY https://github.com/RobotLocomotion/xfoil.git)
set(xfoil_GIT_TAG fde0a9368dd451c93604051fc5704e120073800c)
set(xfoil_IS_PUBLIC TRUE)
Expand Down Expand Up @@ -223,6 +230,7 @@ foreach(proj IN ITEMS
meshconverters
swigmake
swig_matlab
yaml_cpp
drake)
string(TOUPPER ${proj} proj_upper)
if ( ${proj} STREQUAL "drake" OR
Expand Down Expand Up @@ -298,6 +306,7 @@ foreach (proj ${EXTERNAL_PROJECTS})
CMAKE_ARGS
-DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX}
-DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE}
${${proj}_ADDITIONAL_CMAKE_CONFIGURE_ARGS}
DEPENDS download-${proj} ${deps}
${${proj}_ADDITIONAL_BUILD_ARGS}
)
Expand Down
1 change: 1 addition & 0 deletions drake/bindings/python/.gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,4 @@
pydrake/rbtree.py
pydrake/autodiffutils.py
pydrake/solvers/ik.py
*.pyc
1 change: 1 addition & 0 deletions drake/bindings/python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ endfunction(add_python_test)

if (snopt_c_FOUND)
add_python_test(pydrake.test.testRBTIK)
add_python_test(pydrake.test.testPR2IK)
endif()
add_python_test(pydrake.test.testRBTTransformPoints)
add_python_test(pydrake.test.testRBTCoM)
24 changes: 24 additions & 0 deletions drake/bindings/python/pydrake/test/testPR2IK.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
import os
import numpy as np
import pydrake
from pydrake.solvers import ik

robot = pydrake.rbtree.RigidBodyTree(os.path.join(pydrake.getDrakePath(), "examples/PR2/pr2.urdf"))

# Make sure attribute access works on bodies
assert robot.bodies[0].linkname == "world"

constraints = [ik.WorldPositionConstraint(robot, 1,
np.zeros((3,)),
np.array([0,0,1.0]),
np.array([0,0,1.0])),
ik.WorldPositionConstraint(robot, robot.findLink("r_gripper_palm_link").body_index,
np.zeros((3,)),
np.array([0.5,0,1.5]),
np.array([0.5,0,1.5])),
]

q_seed = robot.getZeroConfiguration()
options = ik.IKoptions(robot)
results = ik.inverseKinSimple(robot, q_seed, q_seed, constraints, options)
print repr(results.q_sol)
17 changes: 17 additions & 0 deletions drake/bindings/swig/rbtree.i
Original file line number Diff line number Diff line change
Expand Up @@ -15,16 +15,28 @@

%include <typemaps.i>
%include <std_vector.i>

#define SWIG_SHARED_PTR_NAMESPACE std
// SWIG has built-in support for shared pointers, and can use either std::shared_ptr
// or boost::shared_ptr, since they provide similar enough interfaces. Even though
// the interface file is called 'boost_shared_ptr.i', the above #define tells SWIG
// to use the std:: implementation instead. Note that this does NOT result in any
// boost headers being included.
%include <boost_shared_ptr.i>

%include <eigen.i>
%include <autodiff.i>
%import <autodiffutils.i>

%template(vectorVectorXd) std::vector<Eigen::VectorXd>;
%template(vectorMatrixXd) std::vector<Eigen::MatrixXd>;
%template(vectorString) std::vector<std::string>;
%shared_ptr(RigidBody)
%template(vectorRigidBody) std::vector<std::shared_ptr<RigidBody> >;

%eigen_typemaps(Eigen::VectorXd)
%eigen_typemaps(Eigen::Matrix<double, SPACE_DIMENSION, 1>)
%eigen_typemaps(Eigen::Matrix3Xd)
%eigen_typemaps(Eigen::Matrix<double, SPACE_DIMENSION, Eigen::Dynamic>)
%eigen_typemaps(Eigen::MatrixXd)
%eigen_typemaps(Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic>)
Expand All @@ -37,6 +49,11 @@
%template(AutoDiff3XDynamic) AutoDiffWrapper<Eigen::VectorXd, SPACE_DIMENSION, Eigen::Dynamic>;
%template(AutoDiff3XMax73) AutoDiffWrapper<Eigen::Matrix<double, Eigen::Dynamic, 1, 0, 73>, SPACE_DIMENSION, Eigen::Dynamic>;

%ignore RigidBody::setJoint(std::unique_ptr<DrakeJoint> joint); // unique_ptr confuses SWIG, so we'll ignore it for now
%include "drake/systems/plants/RigidBody.h"

%immutable RigidBodyTree::actuators;
%immutable RigidBodyTree::loops;
%include "drake/systems/plants/RigidBodyTree.h"
%extend RigidBodyTree {
KinematicsCache<double> doKinematics(const Eigen::MatrixBase<Eigen::VectorXd>& q, const Eigen::MatrixBase<Eigen::VectorXd>& v) {
Expand Down
2 changes: 1 addition & 1 deletion drake/core/Core.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,4 +6,4 @@
#include "Function.h"
#include "Gradient.h"

#endif //DRAKE_DRAKECORE_H
#endif // DRAKE_DRAKECORE_H
Loading

0 comments on commit 269db65

Please sign in to comment.