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
00035
00036 #include <sick_tim/sick_tim_common_usb.h>
00037 #include <sick_tim/sick_tim_common_tcp.h>
00038 #include <sick_tim/sick_tim_common_mockup.h>
00039 #include <sick_tim/sick_tim551_2050001_parser.h>
00040
00041 int main(int argc, char **argv)
00042 {
00043 ros::init(argc, argv, "sick_tim551_2050001");
00044 ros::NodeHandle nhPriv("~");
00045
00046
00047 bool useTCP = false;
00048 std::string hostname;
00049 if(nhPriv.getParam("hostname", hostname)) {
00050 useTCP = true;
00051 }
00052 std::string port;
00053 nhPriv.param<std::string>("port", port, "2112");
00054
00055 int timelimit;
00056 nhPriv.param("timelimit", timelimit, 5);
00057
00058 bool subscribe_datagram;
00059 int device_number;
00060 nhPriv.param("subscribe_datagram", subscribe_datagram, false);
00061 nhPriv.param("device_number", device_number, 0);
00062
00063 sick_tim::SickTim5512050001Parser* parser = new sick_tim::SickTim5512050001Parser();
00064
00065 double param;
00066 if (nhPriv.getParam("range_min", param))
00067 {
00068 parser->set_range_min(param);
00069 }
00070 if (nhPriv.getParam("range_max", param))
00071 {
00072 parser->set_range_max(param);
00073 }
00074 if (nhPriv.getParam("time_increment", param))
00075 {
00076 parser->set_time_increment(param);
00077 }
00078
00079 sick_tim::SickTimCommon* s = NULL;
00080
00081 int result = sick_tim::ExitError;
00082 while (ros::ok())
00083 {
00084
00085 if (subscribe_datagram)
00086 s = new sick_tim::SickTimCommonMockup(parser);
00087 else if (useTCP)
00088 s = new sick_tim::SickTimCommonTcp(hostname, port, timelimit, parser);
00089 else
00090 s = new sick_tim::SickTimCommonUsb(parser, device_number);
00091 result = s->init();
00092
00093 while(ros::ok() && (result == sick_tim::ExitSuccess)){
00094 ros::spinOnce();
00095 result = s->loopOnce();
00096 }
00097
00098 delete s;
00099
00100 if (result == sick_tim::ExitFatal)
00101 return result;
00102
00103 if (ros::ok() && !subscribe_datagram && !useTCP)
00104 ros::Duration(1.0).sleep();
00105 }
00106
00107 delete parser;
00108 return result;
00109 }