Skip to content

Commit

Permalink
Merge pull request #2067 from jwnimmer-tri/kill-Core.h
Browse files Browse the repository at this point in the history
Remove Core.h
  • Loading branch information
david-german-tri committed Apr 12, 2016
2 parents b06552b + a49289f commit 8f6d48c
Show file tree
Hide file tree
Showing 23 changed files with 46 additions and 17 deletions.
2 changes: 2 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ Unreleased: changes on master, not yet released
[//]: # "Lost functionality or APIs."
### Removed / Deprecated

- [#2067][] `core/Core.h` is removed.
- [#2039][] Ubuntu 12.04 Trusty is no longer supported.

[//]: # "Smaller bug fixes. No API changes."
Expand All @@ -50,6 +51,7 @@ Changes in version v0.9.11 and before are not provided.

[//]: # "You can use PimpMyChangelog to auto-update this list."
[//]: # "https://github.com/pcreux/pimpmychangelog"
[#2067]: https://github.com/RobotLocomotion/drake/issues/2067
[#2039]: https://github.com/RobotLocomotion/drake/issues/2039
[#2027]: https://github.com/RobotLocomotion/drake/issues/2027
[#1953]: https://github.com/RobotLocomotion/drake/issues/1953
Expand Down
2 changes: 1 addition & 1 deletion drake/core/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@

add_subdirectory(test)

drake_install_headers(Core.h Function.h Gradient.h Vector.h)
drake_install_headers(Function.h Gradient.h Vector.h)
9 changes: 0 additions & 9 deletions drake/core/Core.h

This file was deleted.

3 changes: 2 additions & 1 deletion drake/core/test/vector_test.cc
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#include "gtest/gtest.h"

#include "drake/core/Core.h"
#include "drake/core/Function.h"
#include "drake/core/Vector.h"
#include "drake/core/test/pendulum.h"
#include "drake/util/eigen_matrix_compare.h"
#include "drake/util/testUtil.h"
Expand Down
1 change: 1 addition & 0 deletions drake/examples/Acrobot/test/urdfDynamicsTest.cpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#include "drake/Path.h"
#include "drake/examples/Acrobot/Acrobot.h"
#include "drake/systems/plants/RigidBodySystem.h"
#include "drake/util/eigen_matrix_compare.h"
Expand Down
2 changes: 2 additions & 0 deletions drake/examples/Pendulum/runDynamics.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@

#include <iostream>

#include "drake/Path.h"
#include "drake/util/Polynomial.h"
#include "drake/examples/Pendulum/Pendulum.h"
#include "drake/systems/Simulation.h"
Expand Down
2 changes: 2 additions & 0 deletions drake/examples/Pendulum/runEnergyShaping.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
#include <iostream>

#include "drake/Path.h"
#include "drake/examples/Pendulum/Pendulum.h"
#include "drake/systems/Simulation.h"
#include "drake/systems/plants/BotVisualizer.h"
Expand Down
2 changes: 2 additions & 0 deletions drake/examples/Pendulum/runLQR.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
#include <iostream>

#include "drake/Path.h"
#include "drake/examples/Pendulum/Pendulum.h"
#include "drake/systems/Simulation.h"
#include "drake/systems/controllers/LQR.h"
Expand Down
1 change: 1 addition & 0 deletions drake/examples/Pendulum/test/urdfDynamicsTest.cpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#include "drake/Path.h"
#include "drake/examples/Pendulum/Pendulum.h"
#include "drake/systems/plants/RigidBodySystem.h"
#include "drake/util/eigen_matrix_compare.h"
Expand Down
2 changes: 2 additions & 0 deletions drake/examples/Quadrotor/runDynamics.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@

#include <iostream>

#include "drake/Path.h"
#include "drake/systems/LCMSystem.h"
#include "drake/systems/LinearSystem.h"
#include "drake/systems/cascade_system.h"
Expand Down
2 changes: 2 additions & 0 deletions drake/examples/Quadrotor/runLQR.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
#include <iostream>

#include "drake/Path.h"
#include "drake/examples/Quadrotor/Quadrotor.h"
#include "drake/systems/Simulation.h"
#include "drake/systems/controllers/LQR.h"
Expand Down
1 change: 1 addition & 0 deletions drake/examples/Quadrotor/test/urdfDynamicsTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include "gtest/gtest.h"

#include "drake/Path.h"
#include "drake/systems/plants/RigidBodySystem.h"
#include "drake/util/eigen_matrix_compare.h"
#include "drake/util/testUtil.h"
Expand Down
5 changes: 4 additions & 1 deletion drake/solvers/Optimization.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,10 @@
#include <memory>
#include <initializer_list>
#include <Eigen/Core>
#include "drake/core/Core.h"

#include "drake/core/Function.h"
#include "drake/core/Gradient.h"
#include "drake/core/Vector.h"
#include "drake/drakeOptimization_export.h"
#include "drake/solvers/Constraint.h"
#include "drake/solvers/MathematicalProgram.h"
Expand Down
5 changes: 4 additions & 1 deletion drake/systems/System.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,10 @@
#include <memory>
#include <Eigen/Core>
#include <Eigen/Dense>
#include "drake/core/Core.h"

#include "drake/core/Function.h"
#include "drake/core/Gradient.h"
#include "drake/core/Vector.h"

namespace Drake {

Expand Down
5 changes: 4 additions & 1 deletion drake/systems/cascade_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,10 @@
#define DRAKE_SYSTEMS_CASCADE_SYSTEM_H_

#include <memory>
#include "drake/core/Core.h"

#include "drake/core/Function.h"
#include "drake/core/Gradient.h"
#include "drake/core/Vector.h"
#include "drake/systems/System.h"

namespace Drake {
Expand Down
4 changes: 3 additions & 1 deletion drake/systems/controllers/LQR.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,9 @@
#ifndef DRAKE_SYSTEMS_CONTROLLERS_LQR_H_
#define DRAKE_SYSTEMS_CONTROLLERS_LQR_H_

#include "drake/core/Core.h"
#include "drake/core/Function.h"
#include "drake/core/Gradient.h"
#include "drake/core/Vector.h"
#include "drake/systems/LinearSystem.h"
#include "drake/util/drakeGradientUtil.h"
#include "drake/util/drakeUtil.h"
Expand Down
5 changes: 4 additions & 1 deletion drake/systems/feedback_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,10 @@
#define DRAKE_SYSTEMS_FEEDBACK_SYSTEM_H_

#include <memory>
#include "drake/core/Core.h"

#include "drake/core/Function.h"
#include "drake/core/Gradient.h"
#include "drake/core/Vector.h"
#include "drake/systems/System.h"

namespace Drake {
Expand Down
5 changes: 4 additions & 1 deletion drake/systems/pd_control_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,10 @@
#define DRAKE_SYSTEMS_PD_CONTROL_SYSTEM_H_

#include <memory>
#include "drake/core/Core.h"

#include "drake/core/Function.h"
#include "drake/core/Gradient.h"
#include "drake/core/Vector.h"
#include "drake/systems/System.h"

namespace Drake {
Expand Down
1 change: 1 addition & 0 deletions drake/systems/plants/test/lidarTest.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@

#include <cmath>
#include "lcmtypes/bot_core/planar_lidar_t.hpp"
#include "drake/Path.h"
#include "drake/systems/LCMSystem.h"
#include "drake/systems/plants/RigidBodySystem.h"
#include "drake/systems/plants/BotVisualizer.h"
Expand Down
1 change: 1 addition & 0 deletions drake/systems/plants/test/testAccelerometer.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include "gtest/gtest.h"

#include "drake/Path.h"
#include "drake/systems/plants/RigidBodySystem.h"
#include "drake/util/eigen_matrix_compare.h"
#include "drake/util/testUtil.h"
Expand Down
1 change: 1 addition & 0 deletions drake/systems/plants/test/testGyroscope.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include "gtest/gtest.h"

#include "drake/Path.h"
#include "drake/systems/plants/RigidBodySystem.h"
#include "drake/util/eigen_matrix_compare.h"
#include "drake/util/testUtil.h"
Expand Down
1 change: 1 addition & 0 deletions drake/systems/plants/test/testMagnetometer.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include "gtest/gtest.h"

#include "drake/Path.h"
#include "drake/systems/plants/RigidBodySystem.h"
#include "drake/util/eigen_matrix_compare.h"
#include "drake/util/testUtil.h"
Expand Down
1 change: 1 addition & 0 deletions drake/systems/plants/test/testMassSpringDamper.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include "gtest/gtest.h"

#include "drake/Path.h"
#include "drake/systems/plants/RigidBodySystem.h"
#include "drake/util/eigen_matrix_compare.h"
#include "drake/util/testUtil.h"
Expand Down

0 comments on commit 8f6d48c

Please sign in to comment.