-
Notifications
You must be signed in to change notification settings - Fork 1.3k
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Replaced valuecheckMatrix() with CompareMatrices(). Updated some unit tests use Google Test. #1953
Changes from 54 commits
91843d7
8fcfc5f
88bee2f
7bda976
501272b
dee7a21
d0ef84f
89a89c5
c830214
a48f118
22280db
03a8f75
402c1bc
5e011b8
e0d36de
7624b0f
953e8da
9626cb1
f796068
76334b4
b9e81cc
3853141
b0eb81e
b1b75de
112cf72
8536767
39d02d3
6d45fcf
0e41374
309379a
aa1a892
752cc18
86b0906
16d2ea0
04f2dad
5fc3c8d
32786db
004787c
6548c23
26efb4f
e1311c7
0d32327
74013fe
341e787
f4601e7
84da1a4
707b5a2
8bbeb2f
cea12c4
8396f24
589f7c0
4a4e136
90e1578
c772327
7cb380c
d03d9ae
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,5 +1,6 @@ | ||
if (LCM_FOUND) # only needed because it's using Pendulum.h for examples... | ||
add_executable(testVector testVector.cpp) | ||
add_dependencies(testVector drake_lcmtypes lcmtype_agg_hpp) | ||
add_test(NAME testVector COMMAND testVector) | ||
endif (LCM_FOUND) | ||
if (LCM_FOUND AND GTEST_FOUND) # LCM is only needed because it's using Pendulum.h for examples... | ||
add_executable(vector_test vector_test.cc) | ||
target_link_libraries(vector_test ${GTEST_BOTH_LIBRARIES}) | ||
add_dependencies(vector_test drake_lcmtypes lcmtype_agg_hpp) | ||
add_test(NAME vector_test COMMAND vector_test) | ||
endif (LCM_FOUND AND GTEST_FOUND) |
This file was deleted.
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,142 @@ | ||
#include "gtest/gtest.h" | ||
|
||
#include "drake/examples/Pendulum/Pendulum.h" // to get some types | ||
#include "drake/util/eigen_matrix_compare.h" | ||
#include "drake/util/testUtil.h" | ||
|
||
using Drake::CombinedVector; | ||
using Drake::size; | ||
using Drake::CombinedVectorUtil; | ||
using Drake::NullVector; | ||
using Drake::InputOutputRelation; | ||
using drake::util::MatrixCompareType; | ||
|
||
namespace drake { | ||
namespace core { | ||
namespace { | ||
|
||
// Tests the ability to set a PendulumState equal to a vector and vice versa. | ||
TEST(VectorTest, ValueAssignment) { | ||
Eigen::Vector2d x; | ||
x << 0.2, 0.4; | ||
|
||
PendulumState<double> state; | ||
state.theta = 0.2; | ||
state.thetadot = 0.3; | ||
|
||
EXPECT_EQ(size(state), 2); | ||
|
||
state = x; | ||
EXPECT_EQ(state.theta, 0.2); | ||
EXPECT_EQ(state.thetadot, 0.4); | ||
|
||
state.theta = 0.5; | ||
x = toEigen(state); | ||
EXPECT_EQ(x(0), 0.5); | ||
|
||
Eigen::VectorXd y = toEigen(state); | ||
const double tolerance = 1e-8; | ||
|
||
std::string error_msg; | ||
EXPECT_TRUE( | ||
CompareMatrices(x, y, tolerance, MatrixCompareType::absolute, &error_msg)) | ||
<< error_msg; | ||
} | ||
|
||
// Tests the ability to set a CombinedVector's value | ||
TEST(VectorTest, CombinedVector) { | ||
Eigen::Vector3d abc; | ||
abc << 1, 2, 3; | ||
|
||
CombinedVector<double, PendulumState, PendulumInput> test(abc); | ||
test = 2 * abc; | ||
|
||
EXPECT_EQ(test.first().theta, 2.0); | ||
EXPECT_EQ(test.first().thetadot, 4.0); | ||
EXPECT_EQ(test.second().tau, 6.0); | ||
} | ||
|
||
// Tests the ability to use a CombinedVectorUtil | ||
TEST(VectorTest, CombinedVectorUtil) { | ||
Eigen::Vector3d abc; | ||
abc << 1, 2, 3; | ||
|
||
CombinedVectorUtil<PendulumState, PendulumInput>::type<double> test(abc); | ||
test = 2 * abc; | ||
EXPECT_EQ(test.first().theta, 2.0); | ||
EXPECT_EQ(test.first().thetadot, 4.0); | ||
EXPECT_EQ(test.second().tau, 6.0); | ||
} | ||
|
||
// Verify that combining a vector with an unused or empty vector returns the | ||
// original type | ||
TEST(VectorTest, CombineVectorCornerCases) { | ||
CombinedVectorUtil<PendulumState, NullVector>::type<double> test1; | ||
EXPECT_TRUE((is_same<PendulumState<double>, decltype(test1)>::value)) | ||
<< "combined vector builder returned " + | ||
static_cast<string>(typeid(test1).name()); | ||
|
||
CombinedVectorUtil<NullVector, PendulumState>::type<double> test2; | ||
EXPECT_TRUE((is_same<PendulumState<double>, decltype(test2)>::value)) | ||
<< "combined vector builder returned " + | ||
static_cast<string>(typeid(test2).name()); | ||
} | ||
|
||
// Tests the RowsAtCompileTime | ||
TEST(VectorTest, RowsAtCompileTime) { | ||
EXPECT_EQ((Eigen::Matrix<double, 2, 1>::RowsAtCompileTime), 2) | ||
<< "failed to evaluate RowsAtCompileTime"; | ||
} | ||
|
||
// Tests the InputOutputRelation. Verify that linear is a polynomial. | ||
TEST(VectorTest, InputOutputRelationLinearIsPolynomial) { | ||
EXPECT_TRUE((InputOutputRelation::isA(InputOutputRelation::Form::LINEAR, | ||
InputOutputRelation::Form::POLYNOMIAL))) | ||
<< "linear is polynomial"; | ||
} | ||
|
||
// Tests the InputOutputRelation. Verify that zero is arbitrary. | ||
TEST(VectorTest, InputOutputRelationZeroIsArbitrary) { | ||
EXPECT_TRUE((InputOutputRelation::isA(InputOutputRelation::Form::ZERO, | ||
InputOutputRelation::Form::ARBITRARY))) | ||
<< "zero is arbitrary"; | ||
} | ||
|
||
// Verifies that the least common ancestor of the I/O relations | ||
// AFFINE, LINEAR, AND POLYNOMIAL is polynomial. | ||
TEST(VectorTest, InputOutputRelationLeastCommonAncestor) { | ||
EXPECT_TRUE(( | ||
InputOutputRelation::leastCommonAncestor( | ||
{InputOutputRelation::Form::AFFINE, InputOutputRelation::Form::LINEAR, | ||
InputOutputRelation::Form::POLYNOMIAL}) == | ||
InputOutputRelation::Form::POLYNOMIAL)) | ||
<< "least common ancestor should be polynomial"; | ||
} | ||
|
||
// Verifies that compositions of I/O relations are as expected | ||
TEST(VectorTest, InputOutputRelationCompositionTests) { | ||
InputOutputRelation g(InputOutputRelation::Form::LINEAR); | ||
InputOutputRelation f(InputOutputRelation::Form::POLYNOMIAL); | ||
|
||
EXPECT_EQ(InputOutputRelation::composeWith(g, f).form, | ||
InputOutputRelation::Form::POLYNOMIAL); | ||
|
||
EXPECT_EQ(InputOutputRelation::composeWith(f, g).form, | ||
InputOutputRelation::Form::POLYNOMIAL); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Looks like everything should be clang-formatted again There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @david-german-tri: I just ran clang-format and noticed it may be violating the style guide's specification on the order of includes. Here is an example change made by clang-format: Shouldn't There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Is the problem that you should use |
||
} | ||
|
||
// Verify that combinations of I/O relations are as expected | ||
TEST(VectorTest, InputOutputRelationCombinationTests) { | ||
InputOutputRelation g(InputOutputRelation::Form::LINEAR); | ||
InputOutputRelation f(InputOutputRelation::Form::POLYNOMIAL); | ||
|
||
EXPECT_EQ(InputOutputRelation::combine(g, f).form, | ||
InputOutputRelation::Form::POLYNOMIAL); | ||
|
||
EXPECT_EQ(InputOutputRelation::combine(f, g).form, | ||
InputOutputRelation::Form::POLYNOMIAL); | ||
} | ||
|
||
} // namespace | ||
} // namespace core | ||
} // namespace drake |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,5 +1,5 @@ | ||
if (LCM_FOUND) | ||
if (LCM_FOUND AND GTEST_FOUND) | ||
add_executable(acrobotURDFDynamicsTest urdfDynamicsTest.cpp) | ||
target_link_libraries(acrobotURDFDynamicsTest drakeRBSystem) | ||
target_link_libraries(acrobotURDFDynamicsTest drakeRBSystem ${GTEST_BOTH_LIBRARIES}) | ||
add_test(NAME acrobotURDFDynamicsTest COMMAND acrobotURDFDynamicsTest) | ||
endif(LCM_FOUND) | ||
endif(LCM_FOUND AND GTEST_FOUND) |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,19 +1,34 @@ | ||
|
||
#include "../Acrobot.h" | ||
#include "drake/examples/Acrobot/Acrobot.h" | ||
#include "gtest/gtest.h" | ||
#include "drake/util/eigen_matrix_compare.h" | ||
#include "drake/systems/plants/RigidBodySystem.h" | ||
#include "drake/util/testUtil.h" | ||
|
||
using namespace std; | ||
using namespace Eigen; | ||
using namespace Drake; | ||
using Drake::RigidBodySystem; | ||
using Drake::getRandomVector; | ||
using Drake::getDrakePath; | ||
using drake::util::MatrixCompareType; | ||
|
||
namespace drake { | ||
namespace examples { | ||
namespace Acobot { | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. acrobot |
||
namespace { | ||
|
||
int main(int argc, char* argv[]) { | ||
// Tests whether the dynamics of Acrobot are the same regardless of whether | ||
// it is loaded via direct Acrobot object instantiation, URDF, or SDF. This | ||
// is done by loading random state and input values into the models and | ||
// verifying | ||
// that their dynamics are identical. | ||
TEST(AcrobotDynamicsTest, ValueAssignment) { | ||
// Create three Acrobot models | ||
auto r = Acrobot(); | ||
|
||
auto r_urdf = RigidBodySystem(); | ||
r_urdf.addRobotFromFile(getDrakePath() + "/examples/Acrobot/Acrobot.urdf", DrakeJoint::FIXED); | ||
r_urdf.addRobotFromFile(getDrakePath() + "/examples/Acrobot/Acrobot.urdf", | ||
DrakeJoint::FIXED); | ||
|
||
auto r_sdf = RigidBodySystem(); | ||
r_sdf.addRobotFromFile(getDrakePath() + "/examples/Acrobot/Acrobot.sdf", DrakeJoint::FIXED); | ||
r_sdf.addRobotFromFile(getDrakePath() + "/examples/Acrobot/Acrobot.sdf", | ||
DrakeJoint::FIXED); | ||
|
||
// for debugging: | ||
/* | ||
|
@@ -23,7 +38,9 @@ int main(int argc, char* argv[]) { | |
// I ran this at the console to see the output: | ||
// dot -Tpng -O /tmp/urdf.dot; dot -Tpng -O /tmp/sdf.dot; open /tmp/*.dot.png | ||
|
||
for (int i = 0; i < 1000; i++) { | ||
// Iterate 1000 times each time sending in random state and input variables | ||
// and verifying that the resulting dynamics are the same. | ||
for (int ii = 0; ii < 1000; ii++) { | ||
auto x0 = getRandomVector<AcrobotState>(); | ||
auto u0 = getRandomVector<AcrobotInput>(); | ||
|
||
|
@@ -47,12 +64,18 @@ int main(int argc, char* argv[]) { | |
*/ | ||
|
||
auto xdot = toEigen(r.dynamics(0.0, x0, u0)); | ||
|
||
auto xdot_urdf = r_urdf.dynamics(0.0, x0_rb, u0_rb); | ||
// cout << "xdot = " << xdot.transpose() << endl; | ||
// cout << "xdot_rb = " << xdot_rb.transpose() << endl; | ||
valuecheckMatrix(xdot_urdf, xdot, 1e-8); | ||
EXPECT_TRUE( | ||
CompareMatrices(xdot_urdf, xdot, 1e-8, MatrixCompareType::absolute)); | ||
|
||
auto xdot_sdf = r_sdf.dynamics(0.0, x0_rb, u0_rb); | ||
valuecheckMatrix(xdot_sdf, xdot, 1e-8); | ||
EXPECT_TRUE( | ||
CompareMatrices(xdot_sdf, xdot, 1e-8, MatrixCompareType::absolute)); | ||
} | ||
} | ||
|
||
} // namespace | ||
} // namespace Acrobot | ||
} // namespace examples | ||
} // namespace drake |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,5 +1,5 @@ | ||
if (LCM_FOUND) | ||
if (LCM_FOUND AND GTEST_FOUND) | ||
add_executable(pendulumURDFDynamicsTest urdfDynamicsTest.cpp) | ||
target_link_libraries(pendulumURDFDynamicsTest drakeRBSystem) | ||
target_link_libraries(pendulumURDFDynamicsTest drakeRBSystem ${GTEST_BOTH_LIBRARIES}) | ||
add_test(NAME pendulumURDFDynamicsTest COMMAND pendulumURDFDynamicsTest) | ||
endif(LCM_FOUND) | ||
endif(LCM_FOUND AND GTEST_FOUND) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Why not check theta also?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Added a check for theta.