Skip to content

Commit

Permalink
Merge pull request RobotLocomotion#3958 from jwnimmer-tri/system1-dea…
Browse files Browse the repository at this point in the history
…dwood

Remove System1 deadwood
  • Loading branch information
jwnimmer-tri authored Oct 31, 2016
2 parents 014bf73 + ab45ff7 commit a72c686
Show file tree
Hide file tree
Showing 11 changed files with 7 additions and 107 deletions.
63 changes: 0 additions & 63 deletions drake/automotive/lcm_tap.h

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@
#include "drake/examples/kuka_iiwa_arm/iiwa_simulation.h"
#include "drake/system1/Simulation.h"
#include "drake/system1/cascade_system.h"
#include "drake/system1/robot_state_tap.h"
#include "drake/systems/plants/RigidBodySystem.h"
#include "drake/systems/plants/robot_state_tap.h"

using drake::CascadeSystem;
using drake::RigidBodySystem;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
#include "drake/system1/Simulation.h"
#include "drake/system1/cascade_system.h"
#include "drake/system1/gravity_compensated_pd_position_control_system.h"
#include "drake/system1/robot_state_tap.h"
#include "drake/systems/plants/RigidBodySystem.h"
#include "drake/systems/plants/robot_state_tap.h"

using drake::AffineSystem;
using drake::CascadeSystem;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#include "drake/system1/Simulation.h"
#include "drake/system1/cascade_system.h"
#include "drake/system1/gravity_compensated_system.h"
#include "drake/systems/plants/robot_state_tap.h"
#include "drake/system1/robot_state_tap.h"

using drake::AffineSystem;
using drake::GravityCompensatedSystem;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
#include "drake/system1/Simulation.h"
#include "drake/system1/cascade_system.h"
#include "drake/system1/pd_control_system.h"
#include "drake/system1/robot_state_tap.h"
#include "drake/systems/plants/RigidBodySystem.h"
#include "drake/systems/plants/robot_state_tap.h"

using drake::AffineSystem;
using Eigen::MatrixXd;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
#include "drake/common/eigen_matrix_compare.h"
#include "drake/solvers/trajectoryOptimization/direct_trajectory_optimization.h"
#include "drake/systems/trajectories/PiecewisePolynomial.h"
#include "drake/system1/vector.h"

using std::vector;
using Eigen::MatrixXd;
Expand Down
3 changes: 2 additions & 1 deletion drake/system1/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,8 @@ drake_install_headers(
simulation_options.h
System.h
vector.h
trajectory_logger.h)
trajectory_logger.h
robot_state_tap.h)

if(lcm_FOUND)
add_library_with_exports(LIB_NAME drakeLCMSystem SOURCE_FILES LCMSystem.cpp)
Expand Down
File renamed without changes.
3 changes: 1 addition & 2 deletions drake/systems/plants/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,7 @@ drake_install_headers(
parser_common.h
parser_sdf.h
parser_urdf.h
rigid_body_loop.h
robot_state_tap.h)
rigid_body_loop.h)

pods_install_pkg_config_file(drake-rbm
LIBS -ldrakeRBM -ldrakeCollision -ldrakeJoints -ldrakeXMLUtil
Expand Down
35 changes: 0 additions & 35 deletions drake/systems/plants/constraint/direct_collocation_constraint.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
#include "drake/solvers/constraint.h"
#include "drake/systems/framework/context.h"
#include "drake/systems/framework/system.h"
#include "drake/system1/System.h"

namespace drake {
namespace systems {
Expand Down Expand Up @@ -62,40 +61,6 @@ class DRAKE_EXPORT DirectCollocationConstraint :
int num_inputs_;
};

/// Implements a dynamic constraint which uses the dynamics function
/// of a system.
template <typename System>
class SystemDirectCollocationConstraint : public DirectCollocationConstraint {
public:
// TODO(sam.creasey) Should this be a const bare ptr?
explicit SystemDirectCollocationConstraint(std::shared_ptr<System> system)
: DirectCollocationConstraint(drake::getNumStates(*system),
drake::getNumInputs(*system)),
system_(system) {}

explicit SystemDirectCollocationConstraint(
const SystemDirectCollocationConstraint& other) = delete;
SystemDirectCollocationConstraint& operator=(
const SystemDirectCollocationConstraint& other) = delete;
explicit SystemDirectCollocationConstraint(
SystemDirectCollocationConstraint&& other) = delete;
SystemDirectCollocationConstraint& operator=(
SystemDirectCollocationConstraint&& other) = delete;

private:
void dynamics(const TaylorVecXd& state,
const TaylorVecXd& input,
TaylorVecXd* xdot) const override {
typename System::template StateVector<TaylorVarXd> x = state;
typename System::template InputVector<TaylorVarXd> u = input;
TaylorVarXd t(1);
t = 0;
*xdot = toEigen(system_->dynamics(t, x, u));
}

std::shared_ptr<System> system_;
};

/// Implements a dynamic constraint which uses the continuous dynamics
/// of a system.
class DRAKE_EXPORT System2DirectCollocationConstraint
Expand Down
1 change: 0 additions & 1 deletion drake/systems/plants/test/testIK.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
#include "drake/systems/plants/RigidBodyIK.h"
#include "drake/systems/plants/RigidBodyTree.h"
#include "drake/systems/plants/constraint/RigidBodyConstraint.h"
#include "drake/system1/vector.h"

using Eigen::Vector2d;
using Eigen::Vector3d;
Expand Down

0 comments on commit a72c686

Please sign in to comment.