Skip to content

Commit

Permalink
Merge pull request RobotLocomotion#3159 from jwnimmer-tri/cars-rename1
Browse files Browse the repository at this point in the history
Introduce Vector1 names for Cars vectors
  • Loading branch information
jwnimmer-tri authored Aug 16, 2016
2 parents 28258ed + 0801806 commit 48ebb0c
Show file tree
Hide file tree
Showing 15 changed files with 76 additions and 68 deletions.
1 change: 0 additions & 1 deletion drake/examples/Cars/car_sim_lcm.cc
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
#include "drake/examples/Cars/car_simulation.h"
#include "drake/examples/Cars/gen/driving_command.h"
#include "drake/systems/LCMSystem.h"
#include "drake/systems/LinearSystem.h"
#include "drake/systems/pd_control_system.h"
Expand Down
26 changes: 12 additions & 14 deletions drake/examples/Cars/car_simulation.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,6 @@
#include <cstdlib>

#include "drake/examples/Cars/curve2.h"
#include "drake/examples/Cars/gen/euler_floating_joint_state.h"
#include "drake/examples/Cars/gen/simple_car_state.h"
#include "drake/examples/Cars/trajectory_car.h"

using drake::AffineSystem;
Expand Down Expand Up @@ -138,7 +136,7 @@ void AddFlatTerrain(const std::shared_ptr<RigidBodyTree>& rigid_body_tree,
}

std::shared_ptr<CascadeSystem<
Gain<DrivingCommand, PDControlSystem<RigidBodySystem>::InputVector>,
Gain<DrivingCommand1, PDControlSystem<RigidBodySystem>::InputVector>,
PDControlSystem<RigidBodySystem>>>
CreateVehicleSystem(std::shared_ptr<RigidBodySystem> rigid_body_sys) {
const auto& tree = rigid_body_sys->getRigidBodyTree();
Expand Down Expand Up @@ -202,9 +200,10 @@ CreateVehicleSystem(std::shared_ptr<RigidBodySystem> rigid_body_sys) {

auto vehicle_sys = cascade(
std::allocate_shared<
Gain<DrivingCommand, PDControlSystem<RigidBodySystem>::InputVector>>(
Eigen::aligned_allocator<Gain<
DrivingCommand, PDControlSystem<RigidBodySystem>::InputVector>>(),
Gain<DrivingCommand1, PDControlSystem<RigidBodySystem>::InputVector>>(
Eigen::aligned_allocator<
Gain<DrivingCommand1,
PDControlSystem<RigidBodySystem>::InputVector>>(),
map_driving_cmd_to_x_d),
vehicle_with_pd);

Expand Down Expand Up @@ -274,30 +273,29 @@ std::shared_ptr<TrajectoryCar> CreateTrajectoryCarSystem(int index) {
return std::make_shared<TrajectoryCar>(curve, kSpeed, start_time);
}

std::shared_ptr<AffineSystem<
NullVector, SimpleCarState, EulerFloatingJointState>>
std::shared_ptr<
AffineSystem<NullVector, SimpleCarState1, EulerFloatingJointState1>>
CreateSimpleCarVisualizationAdapter() {
const int insize = SimpleCarState<double>().size();
const int outsize = EulerFloatingJointState<double>().size();
const int insize = SimpleCarState1<double>().size();
const int outsize = EulerFloatingJointState1<double>().size();
MatrixXd D;
D.setZero(outsize, insize);
D(EulerFloatingJointStateIndices::kX, SimpleCarStateIndices::kX) = 1;
D(EulerFloatingJointStateIndices::kY, SimpleCarStateIndices::kY) = 1;
D(EulerFloatingJointStateIndices::kYaw, SimpleCarStateIndices::kHeading) = 1;
EulerFloatingJointState<double> y0;
EulerFloatingJointState1<double> y0;
return std::make_shared<
AffineSystem<
NullVector,
SimpleCarState,
EulerFloatingJointState>>(
SimpleCarState1,
EulerFloatingJointState1>>(
MatrixXd::Zero(0, 0),
MatrixXd::Zero(0, insize),
VectorXd::Zero(0),
MatrixXd::Zero(outsize, 0),
D, toEigen(y0));
}


SimulationOptions GetCarSimulationDefaultOptions() {
SimulationOptions result;
result.initial_step_size = 5e-3;
Expand Down
9 changes: 3 additions & 6 deletions drake/examples/Cars/car_simulation.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,7 @@
#include <Eigen/Geometry>

#include "drake/drakeCars_export.h"
#include "drake/examples/Cars/gen/driving_command.h"
#include "drake/examples/Cars/gen/euler_floating_joint_state.h"
#include "drake/examples/Cars/gen/simple_car_state.h"
#include "drake/examples/Cars/system1_cars_vectors.h"
#include "drake/examples/Cars/trajectory_car.h"
#include "drake/systems/LinearSystem.h"
#include "drake/systems/Simulation.h"
Expand Down Expand Up @@ -113,11 +111,10 @@ void AddFlatTerrain(const std::shared_ptr<RigidBodyTree>& rigid_body_tree,
*/
DRAKECARS_EXPORT
std::shared_ptr<CascadeSystem<
Gain<DrivingCommand, PDControlSystem<RigidBodySystem>::InputVector>,
Gain<DrivingCommand1, PDControlSystem<RigidBodySystem>::InputVector>,
PDControlSystem<RigidBodySystem>>>
CreateVehicleSystem(std::shared_ptr<RigidBodySystem> rigid_body_sys);


/**
* Creates a TrajectoryCar system with a fixed trajectory.
* The details of the trajectory are not documented / promised by this API.
Expand All @@ -133,7 +130,7 @@ std::shared_ptr<TrajectoryCar> CreateTrajectoryCarSystem(int index);
*/
DRAKECARS_EXPORT
std::shared_ptr<drake::AffineSystem<
drake::NullVector, SimpleCarState, EulerFloatingJointState>>
drake::NullVector, SimpleCarState1, EulerFloatingJointState1>>
CreateSimpleCarVisualizationAdapter();

/**
Expand Down
1 change: 0 additions & 1 deletion drake/examples/Cars/demo_multi_car.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
#include "drake/systems/plants/RigidBodyTree.h"

#include "drake/examples/Cars/car_simulation.h"
#include "drake/examples/Cars/gen/euler_floating_joint_state.h"
#include "drake/examples/Cars/trajectory_car.h"

using drake::AffineSystem;
Expand Down
1 change: 0 additions & 1 deletion drake/examples/Cars/multi_car_sim_lcm.cc
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
#include "drake/examples/Cars/car_simulation.h"
#include "drake/examples/Cars/gen/driving_command.h"
#include "drake/common/drake_path.h"
#include "drake/systems/LCMSystem.h"
#include "drake/systems/LinearSystem.h"
Expand Down
7 changes: 4 additions & 3 deletions drake/examples/Cars/run_demo_multi_car.sh
Original file line number Diff line number Diff line change
Expand Up @@ -23,11 +23,12 @@ me=$(readlink -f $0)
mydir=$(dirname $0)
DRAKE=$(readlink -f $mydir/../..)
DRAKE_DIST=$(readlink -f $DRAKE/..)
DRAKE_BUILD=${DRAKE_BUILD:-$DRAKE_DIST/build}

$DRAKE_DIST/build/install/bin/bot-spy &
$DRAKE_DIST/build/install/bin/drake-visualizer &
$DRAKE_BUILD/install/bin/bot-spy &
$DRAKE_BUILD/install/bin/drake-visualizer &
sleep 1 # Wait, to be sure drake-visualizer sees the load_robot message.
$DRAKE_DIST/build/drake/bin/demo_multi_car $1 &
$DRAKE_BUILD/drake/bin/demo_multi_car $1 &

wait

Expand Down
2 changes: 0 additions & 2 deletions drake/examples/Cars/simple_car-inl.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,6 @@
#include <Eigen/Geometry>

#include "drake/common/drake_assert.h"
#include "drake/examples/Cars/gen/driving_command.h"
#include "drake/examples/Cars/gen/simple_car_state.h"

namespace drake {

Expand Down
9 changes: 4 additions & 5 deletions drake/examples/Cars/simple_car.h
Original file line number Diff line number Diff line change
@@ -1,8 +1,7 @@
#pragma once

#include "drake/drakeCars_export.h"
#include "drake/examples/Cars/gen/driving_command.h"
#include "drake/examples/Cars/gen/simple_car_state.h"
#include "drake/examples/Cars/system1_cars_vectors.h"
#include "lcmtypes/drake/lcmt_simple_car_config_t.hpp"

namespace drake {
Expand Down Expand Up @@ -56,11 +55,11 @@ class DRAKECARS_EXPORT SimpleCar {
//@{

template <typename ScalarType>
using StateVector = SimpleCarState<ScalarType>;
using StateVector = SimpleCarState1<ScalarType>;
template <typename ScalarType>
using InputVector = DrivingCommand<ScalarType>;
using InputVector = DrivingCommand1<ScalarType>;
template <typename ScalarType>
using OutputVector = SimpleCarState<ScalarType>;
using OutputVector = SimpleCarState1<ScalarType>;

template <typename ScalarType>
StateVector<ScalarType> dynamics(const ScalarType& time,
Expand Down
9 changes: 4 additions & 5 deletions drake/examples/Cars/simple_car_demo.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
#include "drake/common/drake_path.h"

#include "drake/examples/Cars/car_simulation.h"
#include "drake/examples/Cars/gen/euler_floating_joint_state.h"
#include "drake/examples/Cars/lcm_tap.h"
#include "drake/systems/LCMSystem.h"
#include "drake/systems/LinearSystem.h"
Expand Down Expand Up @@ -35,20 +34,20 @@ int do_main(int argc, const char* argv[]) {
drake::GetDrakePath() + "/examples/Cars/models/boxcar.urdf");

auto viz =
std::make_shared<BotVisualizer<EulerFloatingJointState> >(
std::make_shared<BotVisualizer<EulerFloatingJointState1>>(
lcm, tree);

// Make some taps to publish intermediate states to LCM.
auto car_tap = std::make_shared<LcmTap<SimpleCarState> >(lcm);
auto adapter_tap = std::make_shared<LcmTap<EulerFloatingJointState> >(lcm);
auto car_tap = std::make_shared<LcmTap<SimpleCarState1>>(lcm);
auto adapter_tap = std::make_shared<LcmTap<EulerFloatingJointState1>>(lcm);

// Assemble car, adapter, and visualizer, with intervening taps.
auto car_tapped = cascade(car, car_tap);
auto adapter_tapped = cascade(adapter, adapter_tap);
auto adapt_viz = cascade(adapter_tapped, viz);
auto sys = cascade(car_tapped, adapt_viz);

SimpleCarState<double> initial_state;
SimpleCarState1<double> initial_state;
runLCM(sys, lcm, 0, std::numeric_limits<double>::infinity(), initial_state);

return 0;
Expand Down
9 changes: 5 additions & 4 deletions drake/examples/Cars/simple_car_demo.sh
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,13 @@ me=$(readlink -f $0)
mydir=$(dirname $0)
DRAKE=$(readlink -f $mydir/../..)
DRAKE_DIST=$(readlink -f $DRAKE/..)
DRAKE_BUILD=${DRAKE_BUILD:-$DRAKE_DIST/build}

$DRAKE_DIST/build/install/bin/lcm-logger &
$DRAKE_DIST/build/install/bin/bot-spy &
$DRAKE_DIST/build/install/bin/drake-visualizer &
$DRAKE_BUILD/install/bin/lcm-logger &
$DRAKE_BUILD/install/bin/bot-spy &
$DRAKE_BUILD/install/bin/drake-visualizer &
sleep 1 # Wait, to be sure drake-visualizer sees the load_robot message.
$DRAKE_DIST/build/drake/bin/simple_car_demo &
$DRAKE_BUILD/drake/bin/simple_car_demo &
$mydir/steering_command_driver.py &

wait
Expand Down
20 changes: 20 additions & 0 deletions drake/examples/Cars/system1_cars_vectors.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
#pragma once

#include "drake/examples/Cars/gen/driving_command.h"
#include "drake/examples/Cars/gen/euler_floating_joint_state.h"
#include "drake/examples/Cars/gen/simple_car_state.h"
#include "drake/systems/vector.h"

namespace drake {

// TODO(jwnimmer-tri) These renamings are temporary, in order to support the
// incremental porting of Cars from System1 to System2.

template <typename T>
using DrivingCommand1 = class DrivingCommand<T>;
template <typename T>
using EulerFloatingJointState1 = EulerFloatingJointState<T>;
template <typename T>
using SimpleCarState1 = class SimpleCarState<T>;

} // namespace drake
6 changes: 2 additions & 4 deletions drake/examples/Cars/test/car_simulation_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,6 @@
#include "gtest/gtest.h"

#include "drake/examples/Cars/car_simulation.h"
#include "drake/examples/Cars/gen/euler_floating_joint_state.h"
#include "drake/examples/Cars/gen/simple_car_state.h"

namespace drake {
namespace examples {
Expand All @@ -18,8 +16,8 @@ GTEST_TEST(CarSimulationTest, SimpleCarVisualizationAdapter) {

const double time = 0.0;
const drake::NullVector<double> state_vector{};
SimpleCarState<double> input_vector{};
EulerFloatingJointState<double> output_vector{};
SimpleCarState1<double> input_vector{};
EulerFloatingJointState1<double> output_vector{};
output_vector = dut->output(time, state_vector, input_vector);

EXPECT_DOUBLE_EQ(output_vector.x(), 0.0);
Expand Down
8 changes: 4 additions & 4 deletions drake/examples/Cars/test/simple_car_scalartype_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,12 +37,12 @@ GTEST_TEST(SimpleCarScalarTypeTest, CompileTest) {
const SimpleCar dut;

const MST time_zero{};
const SimpleCarState<MST> state_zeros{};
const DrivingCommand<MST> input_zeros{};
const SimpleCarState1<MST> state_zeros{};
const DrivingCommand1<MST> input_zeros{};

const SimpleCarState<MST> dynamics =
const SimpleCarState1<MST> dynamics =
dut.dynamics(time_zero, state_zeros, input_zeros);
const SimpleCarState<MST> output =
const SimpleCarState1<MST> output =
dut.output(time_zero, state_zeros, input_zeros);

// If we compiled, declare victory.
Expand Down
31 changes: 16 additions & 15 deletions drake/examples/Cars/test/simple_car_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
#include "drake/systems/simulation_options.h"
#include "drake/systems/vector.h"
#include "drake/util/eigen_matrix_compare.h"
#include "drake/examples/Cars/system1_cars_vectors.h"

using drake::util::MatrixCompareType;
using drake::NullVector;
Expand Down Expand Up @@ -81,10 +82,10 @@ class HistorySystem {

GTEST_TEST(SimpleCarTest, ZerosIn) {
SimpleCar dut;
SimpleCarState<double> state_zeros;
DrivingCommand<double> input_zeros;
SimpleCarState1<double> state_zeros;
DrivingCommand1<double> input_zeros;

SimpleCarState<double> rates =
SimpleCarState1<double> rates =
dut.dynamics(0., state_zeros, input_zeros);

const double tolerance = 1e-8;
Expand All @@ -93,16 +94,16 @@ GTEST_TEST(SimpleCarTest, ZerosIn) {
}

GTEST_TEST(SimpleCarTest, Accelerating) {
DrivingCommand<double> max_throttle;
DrivingCommand1<double> max_throttle;
max_throttle.set_throttle(1.);

auto car = std::make_shared<SimpleCar>();
SimpleCarState<double> initial_state;
SimpleCarState1<double> initial_state;
auto history_system =
std::make_shared<HistorySystem<SimpleCarState>>(initial_state);
std::make_shared<HistorySystem<SimpleCarState1>>(initial_state);
auto lead_foot = drake::cascade(
drake::cascade(
std::make_shared<ConstantInputSystem<DrivingCommand>>(
std::make_shared<ConstantInputSystem<DrivingCommand1>>(
max_throttle),
car),
history_system);
Expand Down Expand Up @@ -139,19 +140,19 @@ GTEST_TEST(SimpleCarTest, Accelerating) {
}

GTEST_TEST(SimpleCarTest, Braking) {
DrivingCommand<double> max_brake;
DrivingCommand1<double> max_brake;
max_brake.set_brake(1.);

auto car = std::make_shared<SimpleCar>();
SimpleCarState<double> initial_state;
SimpleCarState1<double> initial_state;
double speed = 10.;
initial_state.set_velocity(speed);

auto history_system =
std::make_shared<HistorySystem<SimpleCarState>>(initial_state);
std::make_shared<HistorySystem<SimpleCarState1>>(initial_state);
auto panic_stop = drake::cascade(
drake::cascade(
std::make_shared<ConstantInputSystem<DrivingCommand>>(
std::make_shared<ConstantInputSystem<DrivingCommand1>>(
max_brake),
car),
history_system);
Expand Down Expand Up @@ -182,18 +183,18 @@ GTEST_TEST(SimpleCarTest, Braking) {
}

GTEST_TEST(SimpleCarTest, Steering) {
DrivingCommand<double> left(Eigen::Vector3d(M_PI / 2, 0., 0.));
DrivingCommand1<double> left(Eigen::Vector3d(M_PI / 2, 0., 0.));

auto car = std::make_shared<SimpleCar>();
SimpleCarState<double> initial_state;
SimpleCarState1<double> initial_state;
double speed = 40.;
initial_state.set_velocity(speed);

auto history_system =
std::make_shared<HistorySystem<SimpleCarState>>(initial_state);
std::make_shared<HistorySystem<SimpleCarState1>>(initial_state);
auto brickyard = drake::cascade(
drake::cascade(
std::make_shared<ConstantInputSystem<DrivingCommand>>(left),
std::make_shared<ConstantInputSystem<DrivingCommand1>>(left),
car),
history_system);

Expand Down
5 changes: 2 additions & 3 deletions drake/examples/Cars/trajectory_car.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,7 @@

#include "drake/drakeCars_export.h"
#include "drake/examples/Cars/curve2.h"
#include "drake/examples/Cars/gen/simple_car_state.h"
#include "drake/systems/vector.h"
#include "drake/examples/Cars/system1_cars_vectors.h"

namespace drake {

Expand Down Expand Up @@ -48,7 +47,7 @@ class DRAKECARS_EXPORT TrajectoryCar {
template <typename ScalarType>
using InputVector = drake::NullVector<ScalarType>;
template <typename ScalarType>
using OutputVector = SimpleCarState<ScalarType>;
using OutputVector = SimpleCarState1<ScalarType>;

template <typename ScalarType>
StateVector<ScalarType> dynamics(const ScalarType& time,
Expand Down

0 comments on commit 48ebb0c

Please sign in to comment.