Skip to content

Commit

Permalink
Fix code style
Browse files Browse the repository at this point in the history
  • Loading branch information
Esteve Fernandez committed Apr 17, 2015
1 parent b85dae9 commit 7387479
Show file tree
Hide file tree
Showing 3 changed files with 130 additions and 130 deletions.
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,17 +119,17 @@ class Node
std::shared_ptr<typename ServiceT::Response> &)> callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);

template <typename ParamTypeT>
ParamTypeT get_param(const parameter::ParamName& key) const;
template<typename ParamTypeT>
ParamTypeT get_param(const parameter::ParamName & key) const;

std::vector<parameter::ParamContainer>
get_params(const std::vector<parameter::ParamQuery>& query) const;
get_params(const std::vector<parameter::ParamQuery> & query) const;

bool
has_param(const parameter::ParamQuery& query) const;
has_param(const parameter::ParamQuery & query) const;

template <typename ParamTypeT>
void set_param(const parameter::ParamName& key, const ParamTypeT& value);
template<typename ParamTypeT>
void set_param(const parameter::ParamName & key, const ParamTypeT & value);

private:
RCLCPP_DISABLE_COPY(Node);
Expand Down
24 changes: 13 additions & 11 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -220,40 +220,42 @@ Node::create_service(
return serv;
}

template <typename ParamTypeT>
template<typename ParamTypeT>
ParamTypeT
Node::get_param(const parameter::ParamName& key) const
Node::get_param(const parameter::ParamName & key) const
{
const parameter::ParamContainer pc = this->params_.at(key);
ParamTypeT value;
return pc.get_value<ParamTypeT>(value);
}

template <typename ParamTypeT>
template<typename ParamTypeT>
void
Node::set_param(const parameter::ParamName& key, const ParamTypeT& value)
Node::set_param(const parameter::ParamName & key, const ParamTypeT & value)
{
parameter::ParamContainer pc;
pc.set_value(key, value);
params_[key] = pc;
}

bool
Node::has_param(const parameter::ParamQuery& query) const
Node::has_param(const parameter::ParamQuery & query) const
{
const parameter::ParamName key = query.get_name();
return (params_.find(key) != params_.end());
return params_.find(key) != params_.end();
}

std::vector<parameter::ParamContainer>
Node::get_params(const std::vector<parameter::ParamQuery>& queries) const
Node::get_params(const std::vector<parameter::ParamQuery> & queries) const
{
std::vector<parameter::ParamContainer> result;

for(auto& kv: params_) {
if(std::any_of(queries.cbegin(), queries.cend(),
[&kv](const parameter::ParamQuery& query) {
return kv.first == query.get_name();})) {
for (auto & kv: params_) {
if (std::any_of(queries.cbegin(), queries.cend(),
[&kv](const parameter::ParamQuery & query) {
return kv.first == query.get_name();
}))
{
result.push_back(kv.second);
}
}
Expand Down
224 changes: 111 additions & 113 deletions rclcpp/include/rclcpp/parameter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,134 +27,132 @@ namespace rclcpp

namespace parameter
{
// Datatype for parameter names
typedef std::string ParamName;
// Datatype for parameter names
typedef std::string ParamName;

// Datatype for storing parameter types
enum ParamDataType {INVALID_PARAM, INT_PARAM, DOUBLE_PARAM, STRING_PARAM, BOOL_PARAM};
// Datatype for storing parameter types
enum ParamDataType {INVALID_PARAM, INT_PARAM, DOUBLE_PARAM, STRING_PARAM, BOOL_PARAM};


// Structure to store an arbitrary parameter with templated get/set methods
class ParamContainer
{
public:
ParamDataType typeID_;
ParamName name_;

/* Templated getter */
template <typename T>
T&
get_value (T& value) const;

inline ParamName get_name() const { return name_; };
/* Templated setter */
template <typename T>
void
set_value(const ParamName& name, const T& value);

private:
int64_t int_value_;
double double_value_;
std::string string_value_;
bool bool_value_;
};

template <>
inline int64_t& ParamContainer::get_value(int64_t& value) const
{
if (typeID_!= INT_PARAM)
{
// TODO: use custom exception
throw std::runtime_error("Invalid type");
}
value = int_value_;
return value;
// Structure to store an arbitrary parameter with templated get/set methods
class ParamContainer
{
public:
ParamDataType typeID_;
ParamName name_;

/* Templated getter */
template<typename T>
T &
get_value(T & value) const;

inline ParamName get_name() const {return name_; }
/* Templated setter */
template<typename T>
void
set_value(const ParamName & name, const T & value);

private:
int64_t int_value_;
double double_value_;
std::string string_value_;
bool bool_value_;
};

template<>
inline int64_t & ParamContainer::get_value(int64_t & value) const
{
if (typeID_ != INT_PARAM) {
// TODO: use custom exception
throw std::runtime_error("Invalid type");
}
template <>
inline double& ParamContainer::get_value(double& value) const
{
if (typeID_!= DOUBLE_PARAM)
{
// TODO: use custom exception
throw std::runtime_error("Invalid type");
}
value = double_value_;
return value;
value = int_value_;
return value;
}
template<>
inline double & ParamContainer::get_value(double & value) const
{
if (typeID_ != DOUBLE_PARAM) {
// TODO: use custom exception
throw std::runtime_error("Invalid type");
}
template <>
inline std::string& ParamContainer::get_value(std::string& value) const
{
if (typeID_!= STRING_PARAM)
{
// TODO: use custom exception
throw std::runtime_error("Invalid type");
}
value = string_value_;
return value;
value = double_value_;
return value;
}
template<>
inline std::string & ParamContainer::get_value(std::string & value) const
{
if (typeID_ != STRING_PARAM) {
// TODO: use custom exception
throw std::runtime_error("Invalid type");
}
template <>
inline bool& ParamContainer::get_value(bool& value) const
{
if (typeID_!= BOOL_PARAM)
{
// TODO: use custom exception
throw std::runtime_error("Invalid type");
}
value = bool_value_;
return value;
value = string_value_;
return value;
}
template<>
inline bool & ParamContainer::get_value(bool & value) const
{
if (typeID_ != BOOL_PARAM) {
// TODO: use custom exception
throw std::runtime_error("Invalid type");
}
value = bool_value_;
return value;
}

template <>
inline void ParamContainer::set_value(const ParamName& name, const int64_t& value)
{
typeID_ = INT_PARAM;
int_value_ = value;
}
template<>
inline void ParamContainer::set_value(const ParamName & name, const int64_t & value)
{
typeID_ = INT_PARAM;
int_value_ = value;
}

template <>
inline void ParamContainer::set_value(const ParamName& name, const double& value)
{
typeID_ = DOUBLE_PARAM;
double_value_ = value;
}
template<>
inline void ParamContainer::set_value(const ParamName & name, const double & value)
{
typeID_ = DOUBLE_PARAM;
double_value_ = value;
}

template<>
inline void ParamContainer::set_value(const ParamName & name, const std::string & value)
{
typeID_ = STRING_PARAM;
string_value_ = value;
}

template<>
inline void ParamContainer::set_value(const ParamName & name, const bool & value)
{
typeID_ = BOOL_PARAM;
bool_value_ = value;
}

class ParamQuery
{
public:
ParamQuery(const std::string & name)
: typeID_(INVALID_PARAM), name_(name) {}
ParamQuery(const ParamDataType typeID)
: typeID_(typeID), name_("") {}

template <>
inline void ParamContainer::set_value(const ParamName& name, const std::string& value)
// TODO: make this extendable for potential regex or other dynamic queryies
// Possibly use a generator pattern?
// For now just store a single datatype and provide accessors.

inline ParamDataType get_type() const
{
typeID_ = STRING_PARAM;
string_value_ = value;
return typeID_;
}

template <>
inline void ParamContainer::set_value(const ParamName& name, const bool& value)
inline ParamName get_name() const
{
typeID_ = BOOL_PARAM;
bool_value_ = value;
return name_;
}

class ParamQuery
{
public:
ParamQuery(const std::string& name) : typeID_(INVALID_PARAM), name_(name) {}
ParamQuery(const ParamDataType typeID) : typeID_(typeID), name_("") {}

// TODO: make this extendable for potential regex or other dynamic queryies
// Possibly use a generator pattern?
// For now just store a single datatype and provide accessors.

inline ParamDataType get_type() const
{
return typeID_;
}
inline ParamName get_name() const
{
return name_;
}

private:
ParamDataType typeID_;
ParamName name_;
};
private:
ParamDataType typeID_;
ParamName name_;
};
} /* namespace parameter */
} /* namespace rclcpp */

Expand Down

0 comments on commit 7387479

Please sign in to comment.