Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00024
00025
00026 #include <string>
00027 #include <ros/ros.h>
00028 #include <ros/console.h>
00029 #include <boost/lexical_cast.hpp>
00030
00031 #include "sr_ronex_utilities/sr_ronex_utilities.hpp"
00032
00033
00034
00041 class SrRonexParseParamExample
00042 {
00043 public:
00044 SrRonexParseParamExample()
00045 {
00046 find_general_io_modules_();
00047 }
00048
00049 ~SrRonexParseParamExample() {}
00050
00051 private:
00058 void find_general_io_modules_(void)
00059 {
00060
00061 ros::Rate loop_rate(10);
00062 std::string param;
00063 while ( ros::param::get("/ronex/devices/0/ronex_id", param ) == false )
00064 {
00065 ROS_INFO_STREAM("Waiting for General I/O module to be loaded properly.\n");
00066 loop_rate.sleep();
00067 }
00068
00069 std::string empty_ronex_id("");
00070 int next_ronex_parameter_id = ronex::get_ronex_param_id(empty_ronex_id);
00071
00072
00073 for (int ronex_parameter_id = 0;
00074 ronex_parameter_id < next_ronex_parameter_id;
00075 ronex_parameter_id++)
00076 {
00077
00078 std::string product_id;
00079 std::string product_id_key = ronex::get_ronex_devices_string(ronex_parameter_id, std::string("product_id"));
00080 ros::param::get(product_id_key, product_id);
00081
00082 std::string product_name;
00083 std::string product_name_key = ronex::get_ronex_devices_string(ronex_parameter_id, std::string("product_name"));
00084 ros::param::get(product_name_key, product_name);
00085
00086
00087 std::string path;
00088 std::string path_key = ronex::get_ronex_devices_string(ronex_parameter_id, std::string("path"));
00089 ros::param::get(path_key, path);
00090
00091 std::string ronex_id;
00092 std::string ronex_id_key = ronex::get_ronex_devices_string(ronex_parameter_id, std::string("ronex_id"));
00093 ros::param::get(ronex_id_key, ronex_id);
00094
00095 std::string serial;
00096 std::string serial_key = ronex::get_ronex_devices_string(ronex_parameter_id, std::string("serial"));
00097 ros::param::get(serial_key, serial);
00098
00099 ROS_INFO_STREAM("*** General I/O module " << ronex_parameter_id << " ***");
00100 ROS_INFO_STREAM("product_id = " << product_id);
00101 ROS_INFO_STREAM("product_name = " << product_name);
00102 ROS_INFO_STREAM("ronex_id = " << ronex_id);
00103 ROS_INFO_STREAM("path = " << path);
00104 ROS_INFO_STREAM("serial = " << serial);
00105 }
00106 }
00107
00114 std::string to_string_(int d)
00115 {
00116 return boost::lexical_cast<std::string>(d);
00117 }
00118 };
00119
00120
00121
00122 int main(int argc, char **argv)
00123 {
00124
00125 ros::init(argc, argv, "sr_ronex_parse_parameter_server");
00126
00127
00128 ros::NodeHandle n;
00129
00130
00131
00132 SrRonexParseParamExample example;
00133
00134 return 0;
00135 }
00136
00137