#include <ros/ros.h>#include <ros/package.h>#include <std_msgs/String.h>#include <topic_tools/shape_shifter.h>#include "rosR.h"

Go to the source code of this file.
| Functions | |
| void | rrosDeleteParam (NodeR *handle, char *param) | 
| bool | rrosGetParamBoolean (NodeR *handle, char *param) | 
| double | rrosGetParamDouble (NodeR *handle, char *param) | 
| int | rrosGetParamInteger (NodeR *handle, char *param) | 
| char * | rrosGetParamString (NodeR *handle, char *param) | 
| char * | rrosGetParamType (NodeR *handle, char *param) | 
| void | rrosSetParamBoolean (NodeR *handle, char *param, bool val) | 
| void | rrosSetParamDouble (NodeR *handle, char *param, double val) | 
| void | rrosSetParamInteger (NodeR *handle, char *param, int val) | 
| void | rrosSetParamString (NodeR *handle, char *param, char *val) | 
| void rrosDeleteParam | ( | NodeR * | handle, | 
| char * | param | ||
| ) | 
Definition at line 55 of file ParamR.cpp.
| bool rrosGetParamBoolean | ( | NodeR * | handle, | 
| char * | param | ||
| ) | 
Definition at line 16 of file ParamR.cpp.
| double rrosGetParamDouble | ( | NodeR * | handle, | 
| char * | param | ||
| ) | 
Definition at line 28 of file ParamR.cpp.
| int rrosGetParamInteger | ( | NodeR * | handle, | 
| char * | param | ||
| ) | 
Definition at line 22 of file ParamR.cpp.
| char* rrosGetParamString | ( | NodeR * | handle, | 
| char * | param | ||
| ) | 
Definition at line 34 of file ParamR.cpp.
| char* rrosGetParamType | ( | NodeR * | handle, | 
| char * | param | ||
| ) | 
Definition at line 3 of file ParamR.cpp.
| void rrosSetParamBoolean | ( | NodeR * | handle, | 
| char * | param, | ||
| bool | val | ||
| ) | 
Definition at line 42 of file ParamR.cpp.
| void rrosSetParamDouble | ( | NodeR * | handle, | 
| char * | param, | ||
| double | val | ||
| ) | 
Definition at line 48 of file ParamR.cpp.
| void rrosSetParamInteger | ( | NodeR * | handle, | 
| char * | param, | ||
| int | val | ||
| ) | 
Definition at line 45 of file ParamR.cpp.
| void rrosSetParamString | ( | NodeR * | handle, | 
| char * | param, | ||
| char * | val | ||
| ) | 
Definition at line 51 of file ParamR.cpp.