Skip to content

Commit

Permalink
Move polynomial_encode_decode into its own file
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri committed Oct 29, 2017
1 parent 7566307 commit f8b308f
Show file tree
Hide file tree
Showing 11 changed files with 198 additions and 142 deletions.
25 changes: 24 additions & 1 deletion drake/systems/controllers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -157,6 +157,19 @@ drake_cc_library(
],
)

drake_cc_library(
name = "polynomial_encode_decode",
srcs = ["polynomial_encode_decode.cc"],
hdrs = ["polynomial_encode_decode.h"],
deps = [
"//drake/common/trajectories:piecewise_polynomial",
"//drake/lcmtypes:piecewise_polynomial",
"//drake/lcmtypes:polynomial",
"//drake/lcmtypes:polynomial_matrix",
"//drake/util",
],
)

# This library is empty unless Gurobi is available.
drake_cc_library(
name = "instantaneous_qp_controller",
Expand All @@ -170,6 +183,7 @@ drake_cc_library(
}),
deps = [
":control_util",
":polynomial_encode_decode",
":qp_common",
":yaml_util",
"//drake/common:essential",
Expand All @@ -186,6 +200,8 @@ drake_cc_library(
],
)

# === test/ ===

drake_cc_library(
name = "zmp_test_util",
testonly = 1,
Expand All @@ -196,7 +212,14 @@ drake_cc_library(
],
)

# === test/ ===
drake_cc_googletest(
name = "polynomial_encode_decode_test",
deps = [
":polynomial_encode_decode",
"//drake/common/test_utilities",
"//drake/common/trajectories:random_piecewise_polynomial",
],
)

drake_cc_googletest(
name = "inverse_dynamics_test",
Expand Down
1 change: 1 addition & 0 deletions drake/systems/controllers/InstantaneousQPController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "drake/multibody/parsers/urdf_parser.h"
#include "drake/solvers/fast_qp.h"
#include "drake/systems/controllers/controlUtil.h"
#include "drake/systems/controllers/polynomial_encode_decode.h"
#include "drake/systems/controllers/yaml_util.h"
#include "drake/util/drakeGeometryUtil.h"
#include "drake/util/lcmUtil.h"
Expand Down
48 changes: 48 additions & 0 deletions drake/systems/controllers/polynomial_encode_decode.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
#include "drake/systems/controllers/polynomial_encode_decode.h"

#include <vector>

#include "drake/util/drakeUtil.h"

using Eigen::Dynamic;
using Eigen::Map;
using Eigen::VectorXd;

void encodePolynomial(const Polynomial<double>& polynomial,
// NOLINTNEXTLINE(runtime/references)
drake::lcmt_polynomial& msg) {
eigenVectorToStdVector(polynomial.GetCoefficients(), msg.coefficients);
msg.num_coefficients = polynomial.GetNumberOfCoefficients();
}

Polynomial<double> decodePolynomial(const drake::lcmt_polynomial& msg) {
Map<const VectorXd> coefficients(msg.coefficients.data(),
msg.coefficients.size());
return Polynomial<double>(coefficients);
}

void encodePiecewisePolynomial(
const PiecewisePolynomial<double>& piecewise_polynomial,
// NOLINTNEXTLINE(runtime/references)
drake::lcmt_piecewise_polynomial& msg) {
msg.num_segments = piecewise_polynomial.getNumberOfSegments();
msg.num_breaks = piecewise_polynomial.getNumberOfSegments() + 1;
msg.breaks = piecewise_polynomial.getSegmentTimes();
msg.polynomial_matrices.resize(piecewise_polynomial.getNumberOfSegments());
for (int i = 0; i < piecewise_polynomial.getNumberOfSegments(); ++i) {
encodePolynomialMatrix<Eigen::Dynamic, Eigen::Dynamic>(
piecewise_polynomial.getPolynomialMatrix(i),
msg.polynomial_matrices[i]);
}
}

PiecewisePolynomial<double> decodePiecewisePolynomial(
const drake::lcmt_piecewise_polynomial& msg) {
typedef PiecewisePolynomial<double>::PolynomialMatrix PolynomialMatrix;
std::vector<PolynomialMatrix> polynomial_matrices;
for (size_t i = 0; i < msg.polynomial_matrices.size(); ++i) {
polynomial_matrices.push_back(
decodePolynomialMatrix<Dynamic, Dynamic>(msg.polynomial_matrices[i]));
}
return PiecewisePolynomial<double>(polynomial_matrices, msg.breaks);
}
55 changes: 55 additions & 0 deletions drake/systems/controllers/polynomial_encode_decode.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
#pragma once

#include <Eigen/Core>

#include "drake/common/trajectories/piecewise_polynomial.h"
#include "drake/lcmt_piecewise_polynomial.hpp"
#include "drake/lcmt_polynomial.hpp"
#include "drake/lcmt_polynomial_matrix.hpp"

void encodePolynomial(const Polynomial<double>& polynomial,
// NOLINTNEXTLINE(runtime/references)
drake::lcmt_polynomial& msg);

Polynomial<double> decodePolynomial(
const drake::lcmt_polynomial& msg);

template <int RowsAtCompileTime, int ColsAtCompileTime>
void encodePolynomialMatrix(
const Eigen::Matrix<Polynomial<double>, RowsAtCompileTime,
ColsAtCompileTime>& polynomial_matrix,
// NOLINTNEXTLINE(runtime/references)
drake::lcmt_polynomial_matrix& msg) {
msg.polynomials.clear();
msg.polynomials.resize(polynomial_matrix.rows());
for (int row = 0; row < polynomial_matrix.rows(); ++row) {
auto& polynomial_msg_row = msg.polynomials[row];
polynomial_msg_row.resize(polynomial_matrix.cols());
for (int col = 0; col < polynomial_matrix.cols(); ++col) {
encodePolynomial(polynomial_matrix(row, col), polynomial_msg_row[col]);
}
}
msg.rows = polynomial_matrix.rows();
msg.cols = polynomial_matrix.cols();
}

template <int RowsAtCompileTime, int ColsAtCompileTime>
Eigen::Matrix<Polynomial<double>, RowsAtCompileTime, ColsAtCompileTime>
decodePolynomialMatrix(const drake::lcmt_polynomial_matrix& msg) {
Eigen::Matrix<Polynomial<double>, RowsAtCompileTime, ColsAtCompileTime> ret(
msg.rows, msg.cols);
for (int row = 0; row < msg.rows; ++row) {
for (int col = 0; col < msg.cols; ++col) {
ret(row, col) = decodePolynomial(msg.polynomials[row][col]);
}
}
return ret;
}

void encodePiecewisePolynomial(
const PiecewisePolynomial<double>& piecewise_polynomial,
// NOLINTNEXTLINE(runtime/references)
drake::lcmt_piecewise_polynomial& msg);

PiecewisePolynomial<double> decodePiecewisePolynomial(
const drake::lcmt_piecewise_polynomial& msg);
66 changes: 66 additions & 0 deletions drake/systems/controllers/test/polynomial_encode_decode_test.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
#include "drake/systems/controllers/polynomial_encode_decode.h"

#include <gtest/gtest.h>

#include "drake/common/test_utilities/random_polynomial_matrix.h"
#include "drake/common/trajectories/test/random_piecewise_polynomial.h"
#include "drake/math/random_rotation.h"

using Eigen::Dynamic;
using Eigen::VectorXd;

namespace drake {
namespace {

// TODO(jwnimmer-tri) Unit tests should not use unseeded randomness.

GTEST_TEST(TestLcmUtil, testPolynomial) {
std::default_random_engine generator;
int max_num_coefficients = 5;
std::uniform_int_distribution<> int_distribution(1, max_num_coefficients);
int num_coefficients = int_distribution(generator);
VectorXd coefficients = VectorXd::Random(num_coefficients);
Polynomial<double> poly(coefficients);
drake::lcmt_polynomial msg;
encodePolynomial(poly, msg);
auto poly_back = decodePolynomial(msg);
EXPECT_TRUE(poly.IsApprox(poly_back, 1e-8));
}

GTEST_TEST(TestLcmUtil, testPolynomialMatrix) {
auto poly_matrix = drake::test::RandomPolynomialMatrix<double>(6, 5, 8);
drake::lcmt_polynomial_matrix msg;
encodePolynomialMatrix<Eigen::Dynamic, Eigen::Dynamic>(poly_matrix, msg);
EXPECT_EQ(static_cast<int>(msg.rows), static_cast<int>(poly_matrix.rows()));
EXPECT_EQ(static_cast<int>(msg.cols), static_cast<int>(poly_matrix.cols()));
auto poly_matrix_back = decodePolynomialMatrix<Dynamic, Dynamic>(msg);
EXPECT_EQ(poly_matrix.rows(), poly_matrix_back.rows());
EXPECT_EQ(poly_matrix.cols(), poly_matrix_back.cols());
for (int row = 0; row < msg.rows; ++row) {
for (int col = 0; col < msg.cols; ++col) {
EXPECT_TRUE(
poly_matrix(row, col).IsApprox(poly_matrix_back(row, col), 1e-8));
}
}
}

GTEST_TEST(TestLcmUtil, testPiecewisePolynomial) {
std::default_random_engine generator;
int num_segments = 6;
int rows = 4;
int cols = 7;
int num_coefficients = 3;
std::vector<double> segment_times =
PiecewiseFunction::randomSegmentTimes(num_segments, generator);
PiecewisePolynomial<double> piecewise_polynomial =
test::MakeRandomPiecewisePolynomial<double>(
rows, cols, num_coefficients, segment_times);
drake::lcmt_piecewise_polynomial msg;
encodePiecewisePolynomial(piecewise_polynomial, msg);
auto piecewise_polynomial_back = decodePiecewisePolynomial(msg);
EXPECT_TRUE(piecewise_polynomial_back.isApprox(piecewise_polynomial, 1e-10));
}

} // namespace
} // namespace drake

1 change: 1 addition & 0 deletions drake/systems/robotInterfaces/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ drake_cc_library(
"//drake/math:geometric_transform",
"//drake/math:gradient",
"//drake/multibody:rigid_body_tree",
"//drake/systems/controllers:polynomial_encode_decode",
"//drake/systems/controllers:zmp_util",
"//drake/util",
"//drake/util:lcm_util",
Expand Down
1 change: 1 addition & 0 deletions drake/systems/robotInterfaces/QPLocomotionPlan.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include "drake/math/gradient.h"
#include "drake/math/quaternion.h"
#include "drake/math/rotation_matrix.h"
#include "drake/systems/controllers/polynomial_encode_decode.h"
#include "drake/systems/robotInterfaces/convex_hull.h"
#include "drake/systems/robotInterfaces/verify_subtype_sizes.h"
#include "drake/util/drakeGeometryUtil.h"
Expand Down
4 changes: 0 additions & 4 deletions drake/util/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -28,10 +28,6 @@ drake_cc_library(
hdrs = ["lcmUtil.h"],
deps = [
":util",
"//drake/common/trajectories:piecewise_polynomial",
"//drake/lcmtypes:piecewise_polynomial",
"//drake/lcmtypes:polynomial",
"//drake/lcmtypes:polynomial_matrix",
"//drake/math:geometric_transform",
"@eigen",
"@lcmtypes_bot2_core",
Expand Down
37 changes: 0 additions & 37 deletions drake/util/lcmUtil.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,40 +59,3 @@ drake::TwistVector<double> DecodeTwist(const bot_core::twist_t& msg) {
ret.tail<3>() = DecodeVector3d(msg.linear_velocity);
return ret;
}

void encodePolynomial(const Polynomial<double>& polynomial,
drake::lcmt_polynomial& msg) {
eigenVectorToStdVector(polynomial.GetCoefficients(), msg.coefficients);
msg.num_coefficients = polynomial.GetNumberOfCoefficients();
}

Polynomial<double> decodePolynomial(const drake::lcmt_polynomial& msg) {
Map<const VectorXd> coefficients(msg.coefficients.data(),
msg.coefficients.size());
return Polynomial<double>(coefficients);
}

void encodePiecewisePolynomial(
const PiecewisePolynomial<double>& piecewise_polynomial,
drake::lcmt_piecewise_polynomial& msg) {
msg.num_segments = piecewise_polynomial.getNumberOfSegments();
msg.num_breaks = piecewise_polynomial.getNumberOfSegments() + 1;
msg.breaks = piecewise_polynomial.getSegmentTimes();
msg.polynomial_matrices.resize(piecewise_polynomial.getNumberOfSegments());
for (int i = 0; i < piecewise_polynomial.getNumberOfSegments(); ++i) {
encodePolynomialMatrix<Eigen::Dynamic, Eigen::Dynamic>(
piecewise_polynomial.getPolynomialMatrix(i),
msg.polynomial_matrices[i]);
}
}

PiecewisePolynomial<double> decodePiecewisePolynomial(
const drake::lcmt_piecewise_polynomial& msg) {
typedef PiecewisePolynomial<double>::PolynomialMatrix PolynomialMatrix;
std::vector<PolynomialMatrix> polynomial_matrices;
for (size_t i = 0; i < msg.polynomial_matrices.size(); ++i) {
polynomial_matrices.push_back(
decodePolynomialMatrix<Dynamic, Dynamic>(msg.polynomial_matrices[i]));
}
return PiecewisePolynomial<double>(polynomial_matrices, msg.breaks);
}
50 changes: 2 additions & 48 deletions drake/util/lcmUtil.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,13 @@
#include <iostream>

#include <Eigen/Core>
#include <Eigen/Geometry>
#include "bot_core/position_3d_t.hpp"
#include "bot_core/quaternion_t.hpp"
#include "bot_core/twist_t.hpp"
#include "bot_core/vector_3d_t.hpp"

#include "drake/common/trajectories/piecewise_polynomial.h"
#include "drake/lcmt_piecewise_polynomial.hpp"
#include "drake/lcmt_polynomial.hpp"
#include "drake/lcmt_polynomial_matrix.hpp"
#include "drake/common/eigen_types.h"

void EncodeVector3d(
const Eigen::Ref<const Eigen::Vector3d>& vec, bot_core::vector_3d_t& msg);
Expand All @@ -38,47 +36,3 @@ void EncodeTwist(

drake::TwistVector<double> DecodeTwist(
const bot_core::twist_t& msg);

void encodePolynomial(const Polynomial<double>& polynomial,
drake::lcmt_polynomial& msg);

Polynomial<double> decodePolynomial(
const drake::lcmt_polynomial& msg);

template <int RowsAtCompileTime, int ColsAtCompileTime>
void encodePolynomialMatrix(
const Eigen::Matrix<Polynomial<double>, RowsAtCompileTime,
ColsAtCompileTime>& polynomial_matrix,
drake::lcmt_polynomial_matrix& msg) {
msg.polynomials.clear();
msg.polynomials.resize(polynomial_matrix.rows());
for (int row = 0; row < polynomial_matrix.rows(); ++row) {
auto& polynomial_msg_row = msg.polynomials[row];
polynomial_msg_row.resize(polynomial_matrix.cols());
for (int col = 0; col < polynomial_matrix.cols(); ++col) {
encodePolynomial(polynomial_matrix(row, col), polynomial_msg_row[col]);
}
}
msg.rows = polynomial_matrix.rows();
msg.cols = polynomial_matrix.cols();
}

template <int RowsAtCompileTime, int ColsAtCompileTime>
Eigen::Matrix<Polynomial<double>, RowsAtCompileTime, ColsAtCompileTime>
decodePolynomialMatrix(const drake::lcmt_polynomial_matrix& msg) {
Eigen::Matrix<Polynomial<double>, RowsAtCompileTime, ColsAtCompileTime> ret(
msg.rows, msg.cols);
for (int row = 0; row < msg.rows; ++row) {
for (int col = 0; col < msg.cols; ++col) {
ret(row, col) = decodePolynomial(msg.polynomials[row][col]);
}
}
return ret;
}

void encodePiecewisePolynomial(
const PiecewisePolynomial<double>& piecewise_polynomial,
drake::lcmt_piecewise_polynomial& msg);

PiecewisePolynomial<double> decodePiecewisePolynomial(
const drake::lcmt_piecewise_polynomial& msg);
Loading

0 comments on commit f8b308f

Please sign in to comment.