Skip to content
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

Support loading lists of booleans from parameter server #6

Open
wants to merge 2 commits into
base: melodic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
20 changes: 18 additions & 2 deletions include/rosparam_shortcuts/rosparam_shortcuts.h
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,9 @@ bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::s
bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string &param_name,
std::vector<double> &values);

bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string &param_name,
std::vector<bool> &values);

bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string &param_name, int &value);

bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string &param_name, std::size_t &value);
Expand All @@ -96,11 +99,24 @@ bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::s
/**
* \brief Output a string of values from an array for debugging
* \param array of values
* \tparam ValueType Type of the elements in @values
* \return string of numbers separated by commas
*/
std::string getDebugArrayString(std::vector<double> values);
template <typename ValueType>
std::string getDebugArrayString(std::vector<ValueType> values)
{
std::string debug_values{};
for (const auto &value : values) debug_values += std::to_string(value) + ",";
return debug_values;
}

std::string getDebugArrayString(std::vector<std::string> values);
template <>
std::string getDebugArrayString(std::vector<std::string> values)
{
std::string debug_values{};
for (const auto &value : values) debug_values += value + ",";
return debug_values;
}

/**
* \brief Convert from 6 doubles of [x,y,z] [r,p,y] or 7 doubles of [x, y, z, qw, qx, qy, qz] to a transform
Expand Down
41 changes: 21 additions & 20 deletions src/rosparam_shortcuts.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,27 @@ bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::s
return true;
}

bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string &param_name,
std::vector<bool> &values)
{
// Load a param
if (!nh.hasParam(param_name))
{
ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'.");
return false;
}
nh.getParam(param_name, values);

if (values.empty())
ROS_WARN_STREAM_NAMED(parent_name, "Empty vector for parameter '" << nh.getNamespace() << "/" << param_name << "'"
".");

ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name
<< "' with values [" << getDebugArrayString(values) << "]");

return true;
}

bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string &param_name, int &value)
{
// Load a param
Expand Down Expand Up @@ -233,26 +254,6 @@ bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::s
return true;
}

std::string getDebugArrayString(std::vector<double> values)
{
std::stringstream debug_values;
for (std::size_t i = 0; i < values.size(); ++i)
{
debug_values << values[i] << ",";
}
return debug_values.str();
}

std::string getDebugArrayString(std::vector<std::string> values)
{
std::stringstream debug_values;
for (std::size_t i = 0; i < values.size(); ++i)
{
debug_values << values[i] << ",";
}
return debug_values.str();
}

bool convertDoublesToEigen(const std::string &parent_name, std::vector<double> values, Eigen::Affine3d &transform)
{
if (values.size() == 6)
Expand Down