LocalGuidance
A library that generates velocity references to follow a path.
param_io Namespace Reference

Functions

template<typename T >
std::ostream & operator<< (std::ostream &ostream, const std::vector< T > &vector)
 
template<typename T1 , typename T2 >
std::ostream & operator<< (std::ostream &ostream, const std::map< T1, T2 > &map)
 
std::ostream & operator<< (std::ostream &ostream, const XmlRpc::XmlRpcValue &xmlRpcValue)
 
template<typename ParamT >
bool getParam (const ros::NodeHandle &nh, const std::string &key, ParamT &parameter)
 
template<typename ParamT >
ParamT param (const ros::NodeHandle &nh, const std::string &key, const ParamT &defaultParameter)
 
template<>
bool getParam (const ros::NodeHandle &nh, const std::string &key, uint32_t &parameter)
 
template<>
bool getParam (const ros::NodeHandle &nh, const std::string &key, ros::Time &parameter)
 
template<>
bool getParam (const ros::NodeHandle &nh, const std::string &key, std_msgs::Header &parameter)
 
template<>
bool getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::Vector3 &parameter)
 
template<>
bool getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::Point &parameter)
 
template<>
bool getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::Quaternion &parameter)
 
template<>
bool getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::Pose &parameter)
 
template<>
bool getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::PoseStamped &parameter)
 
template<>
bool getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::Twist &parameter)
 
template<>
bool getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::TwistStamped &parameter)
 
template<>
bool getParam (const ros::NodeHandle &nh, const std::string &key, Eigen::Matrix< double, 3, 1 > &parameter)
 
template<>
bool getParam (const ros::NodeHandle &nh, const std::string &key, Eigen::Quaterniond &parameter)
 
template<>
bool getParam (const ros::NodeHandle &nh, const std::string &key, Eigen::Matrix< double, 2, 1 > &parameter)
 
template<typename T >
getMember (XmlRpc::XmlRpcValue parameter, const std::string &key)
 
template<typename ParamT >
void setParam (const ros::NodeHandle &nh, const std::string &key, const ParamT &param)
 

Function Documentation

template<typename T >
T param_io::getMember ( XmlRpc::XmlRpcValue  parameter,
const std::string &  key 
)
template<typename ParamT >
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
ParamT &  parameter 
)
inline

Interface 1:

template<>
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
uint32_t &  parameter 
)
inline

Template specializations.

template<>
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
ros::Time &  parameter 
)
inline
template<>
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
std_msgs::Header &  parameter 
)
inline
template<>
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
geometry_msgs::Vector3 &  parameter 
)
inline
template<>
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
geometry_msgs::Point &  parameter 
)
inline
template<>
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
geometry_msgs::Quaternion &  parameter 
)
inline
template<>
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
geometry_msgs::Pose &  parameter 
)
inline
template<>
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
geometry_msgs::PoseStamped &  parameter 
)
inline
template<>
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
geometry_msgs::Twist &  parameter 
)
inline
template<>
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
geometry_msgs::TwistStamped &  parameter 
)
inline
template<>
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
Eigen::Matrix< double, 3, 1 > &  parameter 
)
inline
template<>
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
Eigen::Quaterniond &  parameter 
)
inline
template<>
bool param_io::getParam ( const ros::NodeHandle &  nh,
const std::string &  key,
Eigen::Matrix< double, 2, 1 > &  parameter 
)
inline
template<typename T >
std::ostream& param_io::operator<< ( std::ostream &  ostream,
const std::vector< T > &  vector 
)
inline

Ostream overloads.

template<typename T1 , typename T2 >
std::ostream& param_io::operator<< ( std::ostream &  ostream,
const std::map< T1, T2 > &  map 
)
inline
std::ostream& param_io::operator<< ( std::ostream &  ostream,
const XmlRpc::XmlRpcValue &  xmlRpcValue 
)
inline
template<typename ParamT >
ParamT param_io::param ( const ros::NodeHandle &  nh,
const std::string &  key,
const ParamT &  defaultParameter 
)
inline

Interface 2:

template<typename ParamT >
void param_io::setParam ( const ros::NodeHandle &  nh,
const std::string &  key,
const ParamT &  param 
)
inline