Skip to content

Commit

Permalink
Re-commit generated code.
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri committed Aug 17, 2016
1 parent 550c811 commit af25e5a
Show file tree
Hide file tree
Showing 3 changed files with 56 additions and 210 deletions.
83 changes: 17 additions & 66 deletions drake/examples/Cars/gen/driving_command.h
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
// Copyright 2016 Robot Locomotion Group @ CSAIL. All rights reserved.
#pragma once

// This file is generated by a script. Do not edit!
Expand All @@ -8,101 +7,53 @@
#include <string>
#include <Eigen/Core>

#include "drake/systems/framework/basic_state_and_output_vector.h"
#include "lcmtypes/drake/lcmt_driving_command_t.hpp"

namespace drake {

/// Describes the row indices of a DrivingCommand.
struct DrivingCommandIndices {
/// The total number of rows (coordinates).
static const int kNumCoordiates = 3;
static const int kNumCoordinates = 3;

// The index of each individual coordinate.
static const int kSteeringAngle = 0;
static const int kThrottle = 1;
static const int kBrake = 2;
};

/// Models the drake::LCMVector concept.
template <typename ScalarType = double>
class DrivingCommand {
/// Specializes BasicStateAndOutputVector with specific getters and setters.
template <typename T>
class DrivingCommand : public systems::BasicStateAndOutputVector<T> {
public:
// An abbreviation for our row index constants.
typedef DrivingCommandIndices K;

/// @name Getters and Setters
//@{
const ScalarType& steering_angle() const { return value_(K::kSteeringAngle); }
void set_steering_angle(const ScalarType& steering_angle) {
value_(K::kSteeringAngle) = steering_angle;
}
const ScalarType& throttle() const { return value_(K::kThrottle); }
void set_throttle(const ScalarType& throttle) {
value_(K::kThrottle) = throttle;
}
const ScalarType& brake() const { return value_(K::kBrake); }
void set_brake(const ScalarType& brake) { value_(K::kBrake) = brake; }
//@}

/// @name Implement the drake::Vector concept.
//@{

// Even though in practice we have a fixed size, we declare
// ourselves dynamically sized for compatibility with the
// system/framework/vector_interface.h API, and so that we
// can avoid the alignment issues that come into play with
// a fixed-size Eigen::Matrix member field.
static const int RowsAtCompileTime = Eigen::Dynamic;
typedef Eigen::Matrix<ScalarType, RowsAtCompileTime, 1> EigenType;
size_t size() const { return K::kNumCoordiates; }

/// Default constructor. Sets all rows to zero.
DrivingCommand()
: value_(Eigen::Matrix<ScalarType, K::kNumCoordiates, 1>::Zero()) {}

/// Implicit Eigen::Matrix conversion.
template <typename Derived>
// NOLINTNEXTLINE(runtime/explicit) per drake::Vector.
DrivingCommand(const Eigen::MatrixBase<Derived>& value)
: value_(value.segment(0, K::kNumCoordiates)) {}

/// Eigen::Matrix assignment.
template <typename Derived>
DrivingCommand& operator=(const Eigen::MatrixBase<Derived>& value) {
value_ = value.segment(0, K::kNumCoordiates);
return *this;
DrivingCommand() : systems::BasicStateAndOutputVector<T>(K::kNumCoordinates) {
this->SetFromVector(VectorX<T>::Zero(K::kNumCoordinates));
}

/// Magic conversion specialization back to Eigen.
friend EigenType toEigen(const DrivingCommand<ScalarType>& vec) {
return vec.value_;
/// @name Getters and Setters
//@{
const T steering_angle() const { return this->GetAtIndex(K::kSteeringAngle); }
void set_steering_angle(const T& steering_angle) {
this->SetAtIndex(K::kSteeringAngle, steering_angle);
}

/// Magic pretty names for our coordinates. (This is an optional
/// part of the drake::Vector concept, but seems worthwhile.)
friend std::string getCoordinateName(const DrivingCommand<ScalarType>& vec,
unsigned int index) {
switch (index) {
case K::kSteeringAngle:
return "steering_angle";
case K::kThrottle:
return "throttle";
case K::kBrake:
return "brake";
}
throw std::domain_error("unknown coordinate index");
const T throttle() const { return this->GetAtIndex(K::kThrottle); }
void set_throttle(const T& throttle) {
this->SetAtIndex(K::kThrottle, throttle);
}

const T brake() const { return this->GetAtIndex(K::kBrake); }
void set_brake(const T& brake) { this->SetAtIndex(K::kBrake, brake); }
//@}

/// @name Implement the LCMVector concept
//@{
typedef drake::lcmt_driving_command_t LCMMessageType;
static std::string channel() { return "DRIVING_COMMAND"; }
//@}

private:
EigenType value_;
};

template <typename ScalarType>
Expand Down
96 changes: 21 additions & 75 deletions drake/examples/Cars/gen/euler_floating_joint_state.h
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
// Copyright 2016 Robot Locomotion Group @ CSAIL. All rights reserved.
#pragma once

// This file is generated by a script. Do not edit!
Expand All @@ -8,14 +7,15 @@
#include <string>
#include <Eigen/Core>

#include "drake/systems/framework/basic_state_and_output_vector.h"
#include "lcmtypes/drake/lcmt_euler_floating_joint_state_t.hpp"

namespace drake {

/// Describes the row indices of a EulerFloatingJointState.
struct EulerFloatingJointStateIndices {
/// The total number of rows (coordinates).
static const int kNumCoordiates = 6;
static const int kNumCoordinates = 6;

// The index of each individual coordinate.
static const int kX = 0;
Expand All @@ -26,94 +26,40 @@ struct EulerFloatingJointStateIndices {
static const int kYaw = 5;
};

/// Models the drake::LCMVector concept.
template <typename ScalarType = double>
class EulerFloatingJointState {
/// Specializes BasicStateAndOutputVector with specific getters and setters.
template <typename T>
class EulerFloatingJointState : public systems::BasicStateAndOutputVector<T> {
public:
// An abbreviation for our row index constants.
typedef EulerFloatingJointStateIndices K;

/// @name Getters and Setters
//@{
const ScalarType& x() const { return value_(K::kX); }
void set_x(const ScalarType& x) { value_(K::kX) = x; }
const ScalarType& y() const { return value_(K::kY); }
void set_y(const ScalarType& y) { value_(K::kY) = y; }
const ScalarType& z() const { return value_(K::kZ); }
void set_z(const ScalarType& z) { value_(K::kZ) = z; }
const ScalarType& roll() const { return value_(K::kRoll); }
void set_roll(const ScalarType& roll) { value_(K::kRoll) = roll; }
const ScalarType& pitch() const { return value_(K::kPitch); }
void set_pitch(const ScalarType& pitch) { value_(K::kPitch) = pitch; }
const ScalarType& yaw() const { return value_(K::kYaw); }
void set_yaw(const ScalarType& yaw) { value_(K::kYaw) = yaw; }
//@}

/// @name Implement the drake::Vector concept.
//@{

// Even though in practice we have a fixed size, we declare
// ourselves dynamically sized for compatibility with the
// system/framework/vector_interface.h API, and so that we
// can avoid the alignment issues that come into play with
// a fixed-size Eigen::Matrix member field.
static const int RowsAtCompileTime = Eigen::Dynamic;
typedef Eigen::Matrix<ScalarType, RowsAtCompileTime, 1> EigenType;
size_t size() const { return K::kNumCoordiates; }

/// Default constructor. Sets all rows to zero.
EulerFloatingJointState()
: value_(Eigen::Matrix<ScalarType, K::kNumCoordiates, 1>::Zero()) {}

/// Implicit Eigen::Matrix conversion.
template <typename Derived>
// NOLINTNEXTLINE(runtime/explicit) per drake::Vector.
EulerFloatingJointState(const Eigen::MatrixBase<Derived>& value)
: value_(value.segment(0, K::kNumCoordiates)) {}

/// Eigen::Matrix assignment.
template <typename Derived>
EulerFloatingJointState& operator=(const Eigen::MatrixBase<Derived>& value) {
value_ = value.segment(0, K::kNumCoordiates);
return *this;
}

/// Magic conversion specialization back to Eigen.
friend EigenType toEigen(const EulerFloatingJointState<ScalarType>& vec) {
return vec.value_;
}

/// Magic pretty names for our coordinates. (This is an optional
/// part of the drake::Vector concept, but seems worthwhile.)
friend std::string getCoordinateName(
const EulerFloatingJointState<ScalarType>& vec, unsigned int index) {
switch (index) {
case K::kX:
return "x";
case K::kY:
return "y";
case K::kZ:
return "z";
case K::kRoll:
return "roll";
case K::kPitch:
return "pitch";
case K::kYaw:
return "yaw";
}
throw std::domain_error("unknown coordinate index");
: systems::BasicStateAndOutputVector<T>(K::kNumCoordinates) {
this->SetFromVector(VectorX<T>::Zero(K::kNumCoordinates));
}

/// @name Getters and Setters
//@{
const T x() const { return this->GetAtIndex(K::kX); }
void set_x(const T& x) { this->SetAtIndex(K::kX, x); }
const T y() const { return this->GetAtIndex(K::kY); }
void set_y(const T& y) { this->SetAtIndex(K::kY, y); }
const T z() const { return this->GetAtIndex(K::kZ); }
void set_z(const T& z) { this->SetAtIndex(K::kZ, z); }
const T roll() const { return this->GetAtIndex(K::kRoll); }
void set_roll(const T& roll) { this->SetAtIndex(K::kRoll, roll); }
const T pitch() const { return this->GetAtIndex(K::kPitch); }
void set_pitch(const T& pitch) { this->SetAtIndex(K::kPitch, pitch); }
const T yaw() const { return this->GetAtIndex(K::kYaw); }
void set_yaw(const T& yaw) { this->SetAtIndex(K::kYaw, yaw); }
//@}

/// @name Implement the LCMVector concept
//@{
typedef drake::lcmt_euler_floating_joint_state_t LCMMessageType;
static std::string channel() { return "EULER_FLOATING_JOINT_STATE"; }
//@}

private:
EigenType value_;
};

template <typename ScalarType>
Expand Down
87 changes: 18 additions & 69 deletions drake/examples/Cars/gen/simple_car_state.h
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
// Copyright 2016 Robot Locomotion Group @ CSAIL. All rights reserved.
#pragma once

// This file is generated by a script. Do not edit!
Expand All @@ -8,14 +7,15 @@
#include <string>
#include <Eigen/Core>

#include "drake/systems/framework/basic_state_and_output_vector.h"
#include "lcmtypes/drake/lcmt_simple_car_state_t.hpp"

namespace drake {

/// Describes the row indices of a SimpleCarState.
struct SimpleCarStateIndices {
/// The total number of rows (coordinates).
static const int kNumCoordiates = 4;
static const int kNumCoordinates = 4;

// The index of each individual coordinate.
static const int kX = 0;
Expand All @@ -24,88 +24,37 @@ struct SimpleCarStateIndices {
static const int kVelocity = 3;
};

/// Models the drake::LCMVector concept.
template <typename ScalarType = double>
class SimpleCarState {
/// Specializes BasicStateAndOutputVector with specific getters and setters.
template <typename T>
class SimpleCarState : public systems::BasicStateAndOutputVector<T> {
public:
// An abbreviation for our row index constants.
typedef SimpleCarStateIndices K;

/// @name Getters and Setters
//@{
const ScalarType& x() const { return value_(K::kX); }
void set_x(const ScalarType& x) { value_(K::kX) = x; }
const ScalarType& y() const { return value_(K::kY); }
void set_y(const ScalarType& y) { value_(K::kY) = y; }
const ScalarType& heading() const { return value_(K::kHeading); }
void set_heading(const ScalarType& heading) { value_(K::kHeading) = heading; }
const ScalarType& velocity() const { return value_(K::kVelocity); }
void set_velocity(const ScalarType& velocity) {
value_(K::kVelocity) = velocity;
}
//@}

/// @name Implement the drake::Vector concept.
//@{

// Even though in practice we have a fixed size, we declare
// ourselves dynamically sized for compatibility with the
// system/framework/vector_interface.h API, and so that we
// can avoid the alignment issues that come into play with
// a fixed-size Eigen::Matrix member field.
static const int RowsAtCompileTime = Eigen::Dynamic;
typedef Eigen::Matrix<ScalarType, RowsAtCompileTime, 1> EigenType;
size_t size() const { return K::kNumCoordiates; }

/// Default constructor. Sets all rows to zero.
SimpleCarState()
: value_(Eigen::Matrix<ScalarType, K::kNumCoordiates, 1>::Zero()) {}

/// Implicit Eigen::Matrix conversion.
template <typename Derived>
// NOLINTNEXTLINE(runtime/explicit) per drake::Vector.
SimpleCarState(const Eigen::MatrixBase<Derived>& value)
: value_(value.segment(0, K::kNumCoordiates)) {}

/// Eigen::Matrix assignment.
template <typename Derived>
SimpleCarState& operator=(const Eigen::MatrixBase<Derived>& value) {
value_ = value.segment(0, K::kNumCoordiates);
return *this;
}

/// Magic conversion specialization back to Eigen.
friend EigenType toEigen(const SimpleCarState<ScalarType>& vec) {
return vec.value_;
SimpleCarState() : systems::BasicStateAndOutputVector<T>(K::kNumCoordinates) {
this->SetFromVector(VectorX<T>::Zero(K::kNumCoordinates));
}

/// Magic pretty names for our coordinates. (This is an optional
/// part of the drake::Vector concept, but seems worthwhile.)
friend std::string getCoordinateName(const SimpleCarState<ScalarType>& vec,
unsigned int index) {
switch (index) {
case K::kX:
return "x";
case K::kY:
return "y";
case K::kHeading:
return "heading";
case K::kVelocity:
return "velocity";
}
throw std::domain_error("unknown coordinate index");
/// @name Getters and Setters
//@{
const T x() const { return this->GetAtIndex(K::kX); }
void set_x(const T& x) { this->SetAtIndex(K::kX, x); }
const T y() const { return this->GetAtIndex(K::kY); }
void set_y(const T& y) { this->SetAtIndex(K::kY, y); }
const T heading() const { return this->GetAtIndex(K::kHeading); }
void set_heading(const T& heading) { this->SetAtIndex(K::kHeading, heading); }
const T velocity() const { return this->GetAtIndex(K::kVelocity); }
void set_velocity(const T& velocity) {
this->SetAtIndex(K::kVelocity, velocity);
}

//@}

/// @name Implement the LCMVector concept
//@{
typedef drake::lcmt_simple_car_state_t LCMMessageType;
static std::string channel() { return "SIMPLE_CAR_STATE"; }
//@}

private:
EigenType value_;
};

template <typename ScalarType>
Expand Down

0 comments on commit af25e5a

Please sign in to comment.