Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include <sick_tim/sick_mrs1000_communication.h>
00035 #include <sick_tim/sick_mrs1000_parser.h>
00036
00037 int main(int argc, char **argv)
00038 {
00039 ros::init(argc, argv, "sick_mrs_1000");
00040 ros::NodeHandle nhPriv("~");
00041
00042
00043 bool useTCP = false;
00044 std::string hostname;
00045 if(!nhPriv.getParam("hostname", hostname))
00046 {
00047 ROS_FATAL_STREAM("No hostname given!");
00048 return sick_tim::ExitError;
00049 }
00050 std::string port;
00051 nhPriv.param<std::string>("port", port, "2112");
00052
00053 sick_tim::SickMRS1000Parser* parser = new sick_tim::SickMRS1000Parser();
00054
00055 double param;
00056 if (nhPriv.getParam("range_min", param))
00057 {
00058 parser->set_range_min(param);
00059 }
00060 if (nhPriv.getParam("range_max", param))
00061 {
00062 parser->set_range_max(param);
00063 }
00064 if (nhPriv.getParam("time_increment", param))
00065 {
00066 parser->set_time_increment(param);
00067 }
00068
00069 int timelimit;
00070 nhPriv.param("timelimit", timelimit, 5);
00071
00072 sick_tim::SickTimCommon* s = NULL;
00073
00074 int result = sick_tim::ExitError;
00075 while (ros::ok())
00076 {
00077
00078 s = new sick_tim::SickMrs1000Communication(hostname, port, timelimit, parser);
00079 result = s->init();
00080
00081 while(ros::ok() && (result == sick_tim::ExitSuccess)){
00082 ros::spinOnce();
00083 result = s->loopOnce();
00084 }
00085
00086 delete s;
00087
00088 if (result == sick_tim::ExitFatal)
00089 return result;
00090 }
00091
00092 delete parser;
00093 return result;
00094 }