Go to the documentation of this file.00001 #include "ParamR.h"
00002
00003 char* rrosGetParamType(ros::NodeHandle* handle, char* param){
00004 bool val_b;
00005 int val_i;
00006 double val_d;
00007 std::string val_s;
00008
00009 if(handle->getParam(param, val_b)) return "logical";
00010 else if(handle->getParam(param, val_d)) return "double";
00011 else if(handle->getParam(param, val_i)) return "integer";
00012 else if(handle->getParam(param, val_s)) return "character";
00013 else return "NULL";
00014 }
00015
00016 bool rrosGetParamBoolean(ros::NodeHandle* handle, char* param){
00017 bool val;
00018 handle->getParam(param, val);
00019
00020 return val;
00021 }
00022 int rrosGetParamInteger(ros::NodeHandle* handle, char* param){
00023 int val;
00024 handle->getParam(param, val);
00025
00026 return val;
00027 }
00028 double rrosGetParamDouble(ros::NodeHandle* handle, char* param){
00029 double val;
00030 handle->getParam(param, val);
00031
00032 return val;
00033 }
00034 char* rrosGetParamString(ros::NodeHandle* handle, char* param){
00035 std::string val;
00036 handle->getParam(param, val);
00037
00038 return const_cast<char*>(val.c_str());
00039 }
00040
00041
00042
00043 void rrosSetParamBoolean(ros::NodeHandle* handle, char* param, bool val){
00044 handle->setParam(param, val);
00045 }
00046 void rrosSetParamInteger(ros::NodeHandle* handle, char* param, int val){
00047 handle->setParam(param, val);
00048 }
00049 void rrosSetParamDouble (ros::NodeHandle* handle, char* param, double val){
00050 handle->setParam(param, val);
00051 }
00052 void rrosSetParamString (ros::NodeHandle* handle, char* param, char* val){
00053 std::string val_s = val;
00054 handle->setParam(param, val_s);
00055 }
00056
00057
00058 void rrosDeleteParam (ros::NodeHandle* handle, char* param){
00059 handle->deleteParam(param);
00060 }