Skip to content

Commit

Permalink
Yaml extension for Eigen::Matrix and std::unordered_map (#175)
Browse files Browse the repository at this point in the history
Resolves #175
  • Loading branch information
gilwoolee authored and mkoval committed Apr 23, 2017
1 parent 4c08ac5 commit a806042
Show file tree
Hide file tree
Showing 15 changed files with 493 additions and 206 deletions.
49 changes: 49 additions & 0 deletions cmake/FindYamlCpp.cmake
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
# Locate yaml-cpp
#
# This module defines
# YAMLCPP_FOUND - System has yaml-cpp
# YAMLCPP_INCLUDE_DIRS - The yaml-cpp include directories
# YAMLCPP_LIBRARIES - The libraries needed to use yaml-cpp
# YAMLCPP_DEFINITIONS - Compiler switches required for using yaml-cpp
# YAMLCPP_VERSION - The version of yaml-cpp
#
# By default, the dynamic libraries of yaml-cpp will be found. To find the
# static ones instead, set the YAMLCPP_STATIC_LIBRARY variable to TRUE before
# calling find_package(YamlCpp ...).
#
# If yaml-cpp is not installed in a standard path, you can use the YAMLCPP_DIR
# CMake variable to tell CMake where yaml-cpp is.

# Attempt to find static library first if this is set
if(YAMLCPP_STATIC_LIBRARY)
set(YAMLCPP_STATIC libyaml-cpp.a)
endif()

# Set up pkg-config to find yaml-cpp.
find_package(PkgConfig)
pkg_check_modules(PC_YAMLCPP QUIET yaml-cpp)
set(YAMLCPP_DEFINITIONS ${PC_YAMLCPP_CFLAGS_OTHER})

# Find the yaml-cpp include directory.
find_path(YAMLCPP_INCLUDE_DIR yaml-cpp/yaml.h
HINTS ${PC_YAMLCPP_INCLUDEDIR} ${PC_YAMLCPP_INCLUDE_DIRS}
PATHS ${YAMLCPP_DIR}/include/
PATH_SUFFIXES include)

# Find the yaml-cpp library.
find_library(YAMLCPP_LIBRARY NAMES ${YAMLCPP_STATIC} yaml-cpp
HINTS ${PC_YAMLCPP_LIBDIR} ${PC_YAMLCPP_LIBRARY_DIRS}
PATHS ${YAMLCPP_DIR}/lib/
PATH_SUFFIXES lib64 lib)

set(YAMLCPP_LIBRARIES ${YAMLCPP_LIBRARY})
set(YAMLCPP_INCLUDE_DIRS ${YAMLCPP_INCLUDE_DIR})

set(YAMLCPP_VERSION ${PC_YAMLCPP_VERSION})

# Handle the QUIETLY and REQUIRED arguments and set YAMLCPP_FOUND to TRUE
# if all listed variables are TRUE.
include(FindPackageHandleStandardArgs)
find_package_handle_standard_args(YAMLCPP DEFAULT_MSG
YAMLCPP_INCLUDE_DIR YAMLCPP_LIBRARY)
mark_as_advanced(YAMLCPP_INCLUDE_DIR YAMLCPP_LIBRARY)
8 changes: 4 additions & 4 deletions cmake/version.hpp.in
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/* config.hpp. Generated by CMake for @PROJECT_NAME@. */
#ifndef AIKIDO_CONFIG_HPP_
#define AIKIDO_CONFIG_HPP_
/* version.hpp. Generated by CMake for @PROJECT_NAME@. */
#ifndef AIKIDO_VERSION_HPP_
#define AIKIDO_VERSION_HPP_

/* Version number */
#define AIKIDO_MAJOR_VERSION @AIKIDO_MAJOR_VERSION@
Expand All @@ -27,4 +27,4 @@
(AIKIDO_MAJOR_VERSION < x || (AIKIDO_MAJOR_VERSION <= x && \
(AIKIDO_MINOR_VERSION < y || (AIKIDO_MINOR_VERSION <= y))))

#endif // #ifndef AIKIDO_CONFIG_HPP_
#endif // #ifndef AIKIDO_VERSION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ bool RnBoxConstraintSampleGenerator<N>::sample(
{
Vectord value(mDistributions.size());

for (size_t i = 0; i < value.size(); ++i)
for (size_t i = 0; i < static_cast<std::size_t>(value.size()); ++i)
value[i] = mDistributions[i](*mRng);

mSpace->setValue(static_cast<typename statespace::R<N>::State*>(_state), value);
Expand Down Expand Up @@ -124,15 +124,15 @@ RBoxConstraint<N>::RBoxConstraint(std::shared_ptr<statespace::R<N>> _space,

const auto dimension = mSpace->getDimension();

if (mLowerLimits.size() != dimension)
if (static_cast<std::size_t>(mLowerLimits.size()) != dimension)
{
std::stringstream msg;
msg << "Lower limits have incorrect dimension: expected "
<< mSpace->getDimension() << ", got " << mLowerLimits.size() << ".";
throw std::invalid_argument(msg.str());
}

if (mUpperLimits.size() != dimension)
if (static_cast<std::size_t>(mUpperLimits.size()) != dimension)
{
std::stringstream msg;
msg << "Upper limits have incorrect dimension: expected "
Expand Down Expand Up @@ -184,7 +184,7 @@ bool RBoxConstraint<N>::isSatisfied(
const auto value = mSpace->getValue(
static_cast<const typename statespace::R<N>::State*>(state));

for (size_t i = 0; i < value.size(); ++i)
for (size_t i = 0; i < static_cast<std::size_t>(value.size()); ++i)
{
if (value[i] < mLowerLimits[i] || value[i] > mUpperLimits[i])
return false;
Expand All @@ -201,7 +201,7 @@ bool RBoxConstraint<N>::project(
Vectord value = mSpace->getValue(
static_cast<const typename statespace::R<N>::State*>(_s));

for (size_t i = 0; i < value.size(); ++i)
for (size_t i = 0; i < static_cast<std::size_t>(value.size()); ++i)
{
if (value[i] < mLowerLimits[i])
value[i] = mLowerLimits[i];
Expand Down Expand Up @@ -250,7 +250,7 @@ void RBoxConstraint<N>::getJacobian(
const size_t dimension = mSpace->getDimension();
_out = Eigen::MatrixXd::Zero(dimension, dimension);

for (size_t i = 0; i < _out.rows(); ++i)
for (size_t i = 0; i < static_cast<std::size_t>(_out.rows()); ++i)
{
if (stateValue[i] < mLowerLimits[i])
_out(i, i) = -1.;
Expand Down
2 changes: 1 addition & 1 deletion include/aikido/perception/AprilTagsModule.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,9 @@
#include <tf/transform_listener.h>
#include <dart/dart.hpp>
#include <aikido/util/CatkinResourceRetriever.hpp>
#include <aikido/util/yaml.hpp>
#include <aikido/perception/AprilTagsDatabase.hpp>
#include <aikido/perception/PerceptionModule.hpp>
#include <yaml-cpp/yaml.h>
#include <memory>


Expand Down
2 changes: 1 addition & 1 deletion include/aikido/perception/YamlAprilTagsDatabase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@
#define AIKIDO_PERCEPTION_YAML_APRILTAGS_DATABASE_H

#include "yaml-cpp/yaml.h"
#include <aikido/perception/eigen_yaml.hpp>
#include <aikido/util/CatkinResourceRetriever.hpp>
#include <aikido/util/yaml.hpp>
#include <dart/common/LocalResourceRetriever.hpp>
#include <dart/dart.hpp>
#include <Eigen/Geometry>
Expand Down
183 changes: 0 additions & 183 deletions include/aikido/perception/eigen_yaml.hpp

This file was deleted.

6 changes: 3 additions & 3 deletions include/aikido/statespace/detail/Rn-impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ template <int N>
void R<N>::setValue(State *_state, const typename R<N>::Vectord &_value) const
{
// TODO: Skip this check in release mode.
if (_value.size() != getDimension()) {
if (static_cast<std::size_t>(_value.size()) != getDimension()) {
std::stringstream msg;
msg << "Value has incorrect size: expected " << getDimension() << ", got "
<< _value.size() << ".";
Expand Down Expand Up @@ -245,7 +245,7 @@ template <int N>
void R<N>::expMap(const Eigen::VectorXd&_tangent, StateSpace::State *_out) const
{
// TODO: Skip this check in release mode.
if (_tangent.size() != getDimension()) {
if (static_cast<std::size_t>(_tangent.size()) != getDimension()) {
std::stringstream msg;
msg << "Tangent vector has incorrect size: expected " << getDimension()
<< ", got " << _tangent.size() << ".";
Expand All @@ -260,7 +260,7 @@ void R<N>::expMap(const Eigen::VectorXd&_tangent, StateSpace::State *_out) const
template <int N>
void R<N>::logMap(const StateSpace::State *_in, Eigen::VectorXd& _tangent) const
{
if (_tangent.size() != getDimension())
if (static_cast<std::size_t>(_tangent.size()) != getDimension())
_tangent.resize(getDimension());

auto in = static_cast<const State *>(_in);
Expand Down
Loading

0 comments on commit a806042

Please sign in to comment.