|
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 ¶meter) |
|
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 ¶meter) |
|
template<> |
bool | getParam (const ros::NodeHandle &nh, const std::string &key, ros::Time ¶meter) |
|
template<> |
bool | getParam (const ros::NodeHandle &nh, const std::string &key, std_msgs::Header ¶meter) |
|
template<> |
bool | getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::Vector3 ¶meter) |
|
template<> |
bool | getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::Point ¶meter) |
|
template<> |
bool | getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::Quaternion ¶meter) |
|
template<> |
bool | getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::Pose ¶meter) |
|
template<> |
bool | getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::PoseStamped ¶meter) |
|
template<> |
bool | getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::Twist ¶meter) |
|
template<> |
bool | getParam (const ros::NodeHandle &nh, const std::string &key, geometry_msgs::TwistStamped ¶meter) |
|
template<> |
bool | getParam (const ros::NodeHandle &nh, const std::string &key, Eigen::Matrix< double, 3, 1 > ¶meter) |
|
template<> |
bool | getParam (const ros::NodeHandle &nh, const std::string &key, Eigen::Quaterniond ¶meter) |
|
template<> |
bool | getParam (const ros::NodeHandle &nh, const std::string &key, Eigen::Matrix< double, 2, 1 > ¶meter) |
|
template<typename T > |
T | getMember (XmlRpc::XmlRpcValue parameter, const std::string &key) |
|
template<typename ParamT > |
void | setParam (const ros::NodeHandle &nh, const std::string &key, const ParamT ¶m) |
|