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 nhPriv.param("subscribe_datagram", subscribe_datagram, false);
00060
00061 sick_tim::SickTim5512050001Parser* parser = new sick_tim::SickTim5512050001Parser();
00062
00063 double param;
00064 if (nhPriv.getParam("range_min", param))
00065 {
00066 parser->set_range_min(param);
00067 }
00068 if (nhPriv.getParam("range_max", param))
00069 {
00070 parser->set_range_max(param);
00071 }
00072 if (nhPriv.getParam("time_increment", param))
00073 {
00074 parser->set_time_increment(param);
00075 }
00076
00077 sick_tim::SickTimCommon* s = NULL;
00078
00079 int result = EXIT_FAILURE;
00080 while (ros::ok())
00081 {
00082
00083 delete s;
00084 if (subscribe_datagram)
00085 s = new sick_tim::SickTimCommonMockup(parser);
00086 else if (useTCP)
00087 s = new sick_tim::SickTimCommonTcp(hostname, port, timelimit, parser);
00088 else
00089 s = new sick_tim::SickTimCommonUsb(parser);
00090 result = s->init();
00091
00092 while(ros::ok() && (result == EXIT_SUCCESS)){
00093 ros::spinOnce();
00094 result = s->loopOnce();
00095 }
00096
00097 if (ros::ok() && !subscribe_datagram && !useTCP)
00098 ros::Duration(1.0).sleep();
00099 }
00100
00101 delete s;
00102 delete parser;
00103 return result;
00104 }