Skip to content

Commit

Permalink
Address comments, fix build issues.
Browse files Browse the repository at this point in the history
  • Loading branch information
tkoolen committed Sep 20, 2016
1 parent 40d23ed commit 9acc420
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 8 deletions.
1 change: 1 addition & 0 deletions drake/util/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ if(lcm_FOUND)
add_library_with_exports(LIB_NAME drakeLCMUtil SOURCE_FILES lcmUtil.cpp)
add_dependencies(drakeLCMUtil drake_lcmtypes_hpp)
target_link_libraries(drakeLCMUtil drakeTrajectories)
target_include_directories(drakeLCMUtil SYSTEM BEFORE PUBLIC ${lcm_headers_dir}) # TODO(#3352)
drake_install_headers(lcmUtil.h)
pods_install_libraries(drakeLCMUtil)
pods_install_pkg_config_file(drake-lcm-util
Expand Down
21 changes: 17 additions & 4 deletions drake/util/drakeUtil.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,14 @@ void eigenToCArrayOfArrays(const Eigen::MatrixBase<Derived>& source,

// note for if/when we split off all Matlab related stuff into a different file:
// this function is not Matlab related
// can only be used when the dimension information of the array is known at
// compile time
/** Copies the elements of a (row or column) Eigen vector to an array.
*
* Can only be used when the dimension information of the array is known at compile time.
* Note that the scalar type of @p source need not match the scalar type of @p destination (@p DestScalar). A static_cast will be performed to convert to elements of @p source to @p DestScalar.
*
* @param[in] source Eigen vector source
* @param[out] destination std::vector destination
*/
template <typename DestScalar, size_t Size, typename Derived>
void eigenVectorToCArray(const Eigen::MatrixBase<Derived>& source,
DestScalar(&destination)[Size]) {
Expand All @@ -71,13 +77,20 @@ void eigenVectorToCArray(const Eigen::MatrixBase<Derived>& source,

// note for if/when we split off all Matlab related stuff into a different file:
// this function is not Matlab related
/** Copies the elements of a (row or column) Eigen vector to a std::vector
*
* Note that the scalar type of @p source need not match the scalar type of @p destination (@p DestScalar). A static_cast will be performed to convert to elements of @p source to @p DestScalar.
*
* @param[in] source Eigen vector source
* @param[out] destination std::vector destination
*/
template <typename DestScalar, typename Derived>
static void eigenVectorToStdVector(const Eigen::MatrixBase<Derived>& source,
void eigenVectorToStdVector(const Eigen::MatrixBase<Derived>& source,
std::vector<DestScalar>& destination) {
DRAKE_ASSERT(source.rows() == 1 || source.cols() == 1);
destination.resize(static_cast<size_t>(source.size()));
for (Eigen::Index i = 0; i < source.size(); i++) {
destination[static_cast<size_t>(i)] = static_cast<DestScalar>(source[i]);
destination[static_cast<size_t>(i)] = static_cast<DestScalar>(source(i));
}
}

Expand Down
9 changes: 5 additions & 4 deletions drake/util/test/testLCMUtil.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ GTEST_TEST(TestLcmUtil, testPiecewisePolynomial) {

GTEST_TEST(TestLcmUtil, testVector3d) {
const int kVectorSize = 3;
Eigen::Vector3d vec = Vector3d::LinSpaced(Sequential, 0, kVectorSize);
const Eigen::Vector3d vec = Vector3d::LinSpaced(Sequential, 0, kVectorSize);
bot_core::vector_3d_t msg;
EncodeVector3d(vec, msg);
Eigen::Vector3d vec_back = DecodeVector3d(msg);
Expand All @@ -70,7 +70,7 @@ GTEST_TEST(TestLcmUtil, testVector3d) {
GTEST_TEST(TestLcmUtil, testQuaternion) {
default_random_engine generator;
generator.seed(0);
auto quaternion = drake::math::UniformlyRandomQuat(generator);
const auto quaternion = drake::math::UniformlyRandomQuat(generator);
bot_core::quaternion_t msg;
EncodeQuaternion(quaternion, msg);
auto quat_back = DecodeQuaternion(msg);
Expand All @@ -85,15 +85,16 @@ GTEST_TEST(TestLcmUtil, testPose) {
pose.linear() = drake::math::UniformlyRandomRotmat(generator);
pose.translation().setLinSpaced(0, drake::kSpaceDimension);
pose.makeAffine();
const Eigen::Isometry3d& const_pose = pose;
bot_core::position_3d_t msg;
EncodePose(pose, msg);
EncodePose(const_pose, msg);
Eigen::Isometry3d pose_back = DecodePose(msg);
EXPECT_TRUE(CompareMatrices(pose.matrix(), pose_back.matrix(), 1e-12,
MatrixCompareType::absolute));
}

GTEST_TEST(TestLcmUtil, testTwist) {
drake::TwistVector<double> twist =
const drake::TwistVector<double> twist =
drake::TwistVector<double>::LinSpaced(Sequential, 0, drake::kTwistSize);
bot_core::twist_t msg;
EncodeTwist(twist, msg);
Expand Down

0 comments on commit 9acc420

Please sign in to comment.