Skip to content

Commit

Permalink
Merge pull request #1843 from RussTedrake/bot_core
Browse files Browse the repository at this point in the history
update from @jhoare and @billhoffman to fix windows builds
  • Loading branch information
RussTedrake committed Mar 11, 2016
2 parents 08a9e06 + a0b11fc commit 2387950
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 16 deletions.
8 changes: 4 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -98,8 +98,8 @@ set(avl_IS_PUBLIC TRUE)
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/billhoffman/bullet-pod.git)
set(bullet_GIT_TAG 914fae2859af4da91b201e151900270cb137af5a)
set(bullet_GIT_REPOSITORY https://github.com/RobotLocomotion/bullet-pod.git)
set(bullet_GIT_TAG 54d0751b50f86481549391961b209f06ac5035f9)
set(bullet_IS_PUBLIC TRUE)
set(bullet_IS_CMAKE_POD TRUE)
set(cmake_GIT_REPOSITORY https://github.com/RobotLocomotion/cmake.git)
Expand Down Expand Up @@ -137,8 +137,8 @@ set(lcm_IS_PUBLIC TRUE)
set(libbot_GIT_REPOSITORY https://github.com/RobotLocomotion/libbot.git)
set(libbot_GIT_TAG 94fe5290329646959e1c27896d529abba81e6d93)
set(libbot_IS_PUBLIC TRUE)
set(bot_core_lcmtypes_GIT_REPOSITORY https://github.com/jhoare/bot_core_lcmtypes)
set(bot_core_lcmtypes_GIT_TAG 15471b23faee6cdc48242eb2dfd4c816f0cbe88a)
set(bot_core_lcmtypes_GIT_REPOSITORY https://github.com/openhumanoids/bot_core_lcmtypes)
set(bot_core_lcmtypes_GIT_TAG e5540921b8df89f33896109284a612dab195c0dd)
set(bot_core_lcmtypes_IS_CMAKE_POD TRUE)
set(bot_core_lcmtypes_IS_PUBLIC TRUE)
set(meshconverters_GIT_REPOSITORY https://github.com/RobotLocomotion/meshConverters.git)
Expand Down
12 changes: 6 additions & 6 deletions drake/examples/Acrobot/test/urdfDynamicsTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,10 @@ using namespace Drake;
int main(int argc, char* argv[]) {
auto r = Acrobot();

auto r_urdf = make_shared<RigidBodySystem>();
r_urdf->addRobotFromFile(getDrakePath() + "/examples/Acrobot/Acrobot.urdf", DrakeJoint::FIXED);
auto r_sdf = make_shared<RigidBodySystem>();
r_sdf->addRobotFromFile(getDrakePath() + "/examples/Acrobot/Acrobot.sdf", DrakeJoint::FIXED);
auto r_urdf = RigidBodySystem();
r_urdf.addRobotFromFile(getDrakePath() + "/examples/Acrobot/Acrobot.urdf", DrakeJoint::FIXED);
auto r_sdf = RigidBodySystem();
r_sdf.addRobotFromFile(getDrakePath() + "/examples/Acrobot/Acrobot.sdf", DrakeJoint::FIXED);

// for debugging:
/*
Expand Down Expand Up @@ -47,12 +47,12 @@ int main(int argc, char* argv[]) {
*/

auto xdot = toEigen(r.dynamics(0.0,x0,u0));
auto xdot_urdf = r_urdf->dynamics(0.0, x0_rb, u0_rb);
auto xdot_urdf = r_urdf.dynamics(0.0, x0_rb, u0_rb);
// cout << "xdot = " << xdot.transpose() << endl;
// cout << "xdot_rb = " << xdot_rb.transpose() << endl;
valuecheckMatrix(xdot_urdf,xdot,1e-8);

auto xdot_sdf = r_sdf->dynamics(0.0, x0_rb, u0_rb);
auto xdot_sdf = r_sdf.dynamics(0.0, x0_rb, u0_rb);
valuecheckMatrix(xdot_sdf,xdot,1e-8);
}
}
6 changes: 3 additions & 3 deletions drake/examples/Pendulum/test/urdfDynamicsTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@ using namespace Drake;

int main(int argc, char* argv[])
{
auto tree = make_shared<RigidBodyTree>(getDrakePath()+"/examples/Pendulum/Pendulum.urdf",DrakeJoint::FIXED);
auto rbsys = make_shared<RigidBodySystem>(tree);
auto tree = shared_ptr<RigidBodyTree>(new RigidBodyTree(getDrakePath()+"/examples/Pendulum/Pendulum.urdf",DrakeJoint::FIXED));
auto rbsys = RigidBodySystem(tree);
auto p = Pendulum();

for (int i = 0; i < 1000; i++) {
Expand All @@ -24,7 +24,7 @@ int main(int argc, char* argv[])


auto xdot = toEigen(p.dynamics(0.0,x0,u0));
auto xdot_rb = rbsys->dynamics(0.0,x0_rb,u0_rb);
auto xdot_rb = rbsys.dynamics(0.0,x0_rb,u0_rb);
valuecheckMatrix(xdot_rb,xdot,1e-8);
}
}
6 changes: 3 additions & 3 deletions drake/examples/Quadrotor/test/urdfDynamicsTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,8 @@ using namespace Drake;

int main(int argc, char* argv[])
{
auto rbsys = make_shared<RigidBodySystem>();
rbsys->addRobotFromFile(getDrakePath()+"/examples/Quadrotor/quadrotor.urdf",DrakeJoint::ROLLPITCHYAW);
auto rbsys = RigidBodySystem();
rbsys.addRobotFromFile(getDrakePath()+"/examples/Quadrotor/quadrotor.urdf",DrakeJoint::ROLLPITCHYAW);

auto p = Quadrotor();

Expand All @@ -22,7 +22,7 @@ int main(int argc, char* argv[])
RigidBodySystem::InputVector<double> u0_rb = toEigen(u0);

auto xdot = toEigen(p.dynamics(0.0,x0,u0));
auto xdot_rb = rbsys->dynamics(0.0,x0_rb,u0_rb);
auto xdot_rb = rbsys.dynamics(0.0,x0_rb,u0_rb);
valuecheckMatrix(xdot_rb,xdot,1e-8);
}
}

0 comments on commit 2387950

Please sign in to comment.