Skip to content

Commit

Permalink
Style guide
Browse files Browse the repository at this point in the history
Minor updates.
  • Loading branch information
jadecastro committed Nov 18, 2016
1 parent 1deba34 commit da616c5
Show file tree
Hide file tree
Showing 7 changed files with 29 additions and 56 deletions.
12 changes: 6 additions & 6 deletions drake/automotive/idm_planner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@ namespace automotive {

template <typename T>
IdmPlanner<T>::IdmPlanner(const T& v_0) : v_0_(v_0) {

// The reference velocity must be strictly positive.
DRAKE_ASSERT(v_0 > 0);

Expand Down Expand Up @@ -49,7 +48,7 @@ void IdmPlanner<T>::EvalOutput(const systems::Context<T>& context,
output->GetMutableVectorData(0);
DRAKE_ASSERT(output_vector != nullptr);

// TODO: bake in David's parameters definition stuff.
// TODO(jadecastro): Bake in David's new parameter definition API.
IdmPlannerParameters<T> params;
params.set_a(T(1.0)); // max acceleration.
params.set_b(T(3.0)); // comfortable braking deceleration.
Expand All @@ -66,10 +65,11 @@ void IdmPlanner<T>::EvalOutput(const systems::Context<T>& context,
const T& l_a = params.l_a();

// @p a and @p b must be positive.
// TODO: the below assertion forbids symbolic::Expressions with this
// construction.
DRAKE_ASSERT( a > 0.0 );
DRAKE_ASSERT( b > 0.0 );

// TODO(jadecastro): the below assertion forbids
// symbolic::Expressions with this construction.
DRAKE_ASSERT(a > 0.0);
DRAKE_ASSERT(b > 0.0);

output_vector->SetAtIndex(
0, a * (1.0 - pow(input_ego->GetAtIndex(1) / v_0_, delta) -
Expand Down
8 changes: 4 additions & 4 deletions drake/automotive/idm_planner.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,23 +5,22 @@
namespace drake {
namespace automotive {

/// IdmPlanner -- an IDM (Intelligent Driver Modal)[1].
/// IdmPlanner -- an IDM (Intelligent Driver Modal) planner.
///
/// [1] IDM: Intelligent Driver Model:
/// IDM: Intelligent Driver Model:
/// https://en.wikipedia.org/wiki/Intelligent_driver_model
///
/// Instantiated templates for the following kinds of T's are provided:
/// - double
/// - drake::TaylorVarXd
/// - drake::symbolic::Expression
///
/// They are already available to link against in libdrakeAutomotive.
///
/// @ingroup automotive_systems
template <typename T>
class IdmPlanner : public systems::LeafSystem<T> {
public:
IdmPlanner(const T& v_0);
explicit IdmPlanner(const T& v_0);
~IdmPlanner() override;

/// The output of this system is an algbraic relation of its inputs.
Expand All @@ -32,6 +31,7 @@ class IdmPlanner : public systems::LeafSystem<T> {
systems::SystemOutput<T>* output) const override;

protected:
// LeafSystem<T> overrides
std::unique_ptr<systems::BasicVector<T>> AllocateOutputVector(
const systems::SystemPortDescriptor<T>& descriptor) const override;

Expand Down
41 changes: 8 additions & 33 deletions drake/automotive/linear_car.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,21 +7,19 @@

#include "drake/common/drake_assert.h"
#include "drake/common/drake_export.h"
#include "drake/common/eigen_autodiff_types.h"
#include "drake/common/symbolic_expression.h"
#include "drake/math/autodiff_overloads.h"
//#include "drake/systems/framework/leaf_context.h"

namespace drake {
namespace automotive {

template <typename T>
LinearCar<T>::LinearCar() {
this->DeclareInputPort(systems::kVectorValued,
1, //LinearCarInputIndices::kNumCoordinates,
1, // Acceleration is the sole input.
systems::kContinuousSampling);
this->DeclareOutputPort(systems::kVectorValued,
2, //LinearCarStateIndices::kNumCoordinates,
2, // Two outputs: x, v.
systems::kContinuousSampling);
}

Expand All @@ -39,9 +37,8 @@ const systems::SystemPortDescriptor<T>& LinearCar<T>::get_output_port() const {
}

template <typename T>
void LinearCar<T>::EvalOutput(
const systems::Context<T>& context,
systems::SystemOutput<T>* output) const {
void LinearCar<T>::EvalOutput(const systems::Context<T>& context,
systems::SystemOutput<T>* output) const {
DRAKE_ASSERT_VOID(systems::System<T>::CheckValidContext(context));
DRAKE_ASSERT_VOID(systems::System<T>::CheckValidOutput(output));

Expand All @@ -50,12 +47,8 @@ void LinearCar<T>::EvalOutput(
output->GetMutableVectorData(0);
DRAKE_ASSERT(output_vector != nullptr);

// TODO(david-german-tri): Remove this copy by allowing output ports to be
// mere pointers to state variables (or cache lines).
//output_vector->get_mutable_value() =
// context.get_continuous_state()->CopyToVector();
this->GetMutableOutputVector(output, 0) =
this->CopyContinuousStateVector(context);
this->CopyContinuousStateVector(context);
}

template <typename T>
Expand All @@ -68,52 +61,34 @@ void LinearCar<T>::EvalTimeDerivatives(
// Obtain the state.
const systems::VectorBase<T>& context_state =
context.get_continuous_state_vector();
//const LinearCarInput<T>* const input =
// dynamic_cast<const LinearCarInput<T>*>(this->EvalVectorInput(context, 0));
auto input = this->EvalVectorInput(context, 0);
//DRAKE_ASSERT(input != nullptr);
//const LinearCarState<T>* const state =
// dynamic_cast<const LinearCarState<T>*>(&context_state);
//DRAKE_ASSERT(state != nullptr);
DRAKE_ASSERT(input != nullptr);

// Obtain the structure we need to write into.
systems::VectorBase<T>* const derivatives_state =
derivatives->get_mutable_vector();
DRAKE_ASSERT(derivatives_state != nullptr);
//LinearCarState<T>* const new_derivatives =
// dynamic_cast<LinearCarState<T>*>(derivatives_state);
//DRAKE_ASSERT(new_derivatives != nullptr);

// Declare the state derivatives (consistent with linear_car_state.cc).
//new_derivatives->set_x(state->v());
//new_derivatives->set_v(input->vdot());
derivatives_state->SetAtIndex(0, context_state.GetAtIndex(1));
derivatives_state->SetAtIndex(1, input->GetAtIndex(0));
}

template <typename T>
std::unique_ptr<systems::ContinuousState<T>>
LinearCar<T>::AllocateContinuousState() const {
//auto state = std::make_unique<LinearCarState<T>>();
// Define the initial state values.
//state->set_x(T{0.0});
//state->set_v(T{0.0});
const int size = systems::System<T>::get_output_port(0).get_size();
//DRAKE_ASSERT(systems::System<T>::get_input_port(0).get_size() == size);
return std::make_unique<systems::ContinuousState<T>>(
std::make_unique<systems::BasicVector<T>>(size));
}

template <typename T>
std::unique_ptr<systems::BasicVector<T>>
LinearCar<T>::AllocateOutputVector(
std::unique_ptr<systems::BasicVector<T>> LinearCar<T>::AllocateOutputVector(
const systems::SystemPortDescriptor<T>& descriptor) const {
//return std::make_unique<LinearCarState<T>>();
return std::make_unique<systems::BasicVector<T>>(2);
}

// These instantiations must match the API documentation in
// idm_with_trajectory_agent.h.
// linear_car.h.
template class DRAKE_EXPORT LinearCar<double>;
template class DRAKE_EXPORT LinearCar<drake::TaylorVarXd>;
template class DRAKE_EXPORT LinearCar<drake::symbolic::Expression>;
Expand Down
3 changes: 0 additions & 3 deletions drake/automotive/linear_car.h
Original file line number Diff line number Diff line change
@@ -1,9 +1,6 @@
#pragma once

//#include "drake/automotive/gen/linear_car_input.h"
//#include "drake/automotive/gen/linear_car_state.h"
#include "drake/systems/framework/leaf_system.h"
//#include "drake/systems/framework/system_output.h"

namespace drake {
namespace automotive {
Expand Down
10 changes: 6 additions & 4 deletions drake/automotive/single_lane_ego_and_agent.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,12 +11,14 @@
namespace drake {
namespace automotive {

/// System with cars arranged in a diagram:
/// System consisting of two cars: an ego and an agent, where the ego
/// is governed by an IDM (intelligent driver model) planner, and
/// where the agent is fed a constant acceleration input.
///
/// +--------------+ +-------------+
/// | Constant | v_dot_a | Agent Car | x_a, v_a
/// | Acceleration |-------->| |----+
/// | Input | | (LinearCar) | |
/// | Acceleration | v_dot_a | Agent Car | x_a, v_a
/// | Input |-------->| |----+
/// | (Constant) | | (LinearCar) | |
/// +--------------+ +-------------+ |
/// |
/// +---------------------------------------+
Expand Down
4 changes: 2 additions & 2 deletions drake/automotive/test/idm_planner_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ TEST_F(IdmPlannerTest, Topology) {
}

TEST_F(IdmPlannerTest, Input) {
// Define a pointer to where the EvalOutput results end up.
// Define a pointer to where the EvalOutput results are stored.
const auto result = output_->get_vector_data(0);
ASSERT_NE(nullptr, result);

Expand Down Expand Up @@ -87,7 +87,7 @@ TEST_F(IdmPlannerTest, Input) {
(x_a - x_e - l_a),
2.0));

// Verify that the starting input is zero.
// The output values should match the expected values.
dut_->EvalOutput(*context_, output_.get());
EXPECT_EQ(expected_output, result->GetAtIndex(0));
}
Expand Down
7 changes: 3 additions & 4 deletions drake/automotive/test/single_lane_ego_and_agent_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,8 @@ class SingleLaneEgoAndAgentTest : public ::testing::Test {

const systems::VectorBase<double>* state_derivatives(
const systems::System<double>* system) {
const systems::ContinuousState<double>* p = derivatives_.get();
const systems::ContinuousState<double>* subderivatives =
dut_.GetSubsystemDerivatives(*p, system);
dut_.GetSubsystemDerivatives(*derivatives_, system);
return &subderivatives->get_vector();
}

Expand Down Expand Up @@ -119,8 +118,8 @@ TEST_F(SingleLaneEgoAndAgentTest, EvalTimeDerivatives) {
ASSERT_NE(nullptr, context_);
ASSERT_NE(nullptr, derivatives_);

// Obtain pointers to the (continuous) state vector, output
// vector, and vector of state derivatives for each car.
// Obtain pointers to the (continuous) state vector and state
// derivative vector for each car.
auto state_vec_ego = continuous_state(dut_.get_ego_car_system());
auto state_vec_agent = continuous_state(dut_.get_agent_car_system());

Expand Down

0 comments on commit da616c5

Please sign in to comment.