diff --git a/cfg/SickScan.cfg b/cfg/SickScan.cfg index 43b4985..9b67568 100755 --- a/cfg/SickScan.cfg +++ b/cfg/SickScan.cfg @@ -68,7 +68,6 @@ gen.add("powerOnCount", int_t ,0, "Read only Power On counter at start up.", gen.add("operationHours", double_t ,0, "Read only operationg hours [h].", 0,0,6553.6) gen.add("locationName", str_t,0, "Device Location Name",""), gen.add("timelimit", double_t, 0, "Network time limit for datagram request [sec].", 5.0, 0.1,100.0) -gen.add("use_binary_protocol", bool_t, 0, "Force usage of binary protocol if true or ASCII if false, if not set default protocol is used.", True) gen.add("cloud_output_mode", int_t, 0, "[0] Pointcloud is dense all layers in one cloud,[1] Each layer in its own cloud message to improve timestamp accuracy,[2] layers are split to achieve approx. 1 KHz data rate", 0,0,2) gen.add("ang_res", double_t, 0, "Angular resolution in deg/scan set to 0 to use scanner default", 0 ,0,10) gen.add("scan_freq", double_t, 0, "Scan frequency set to 0 to use scanner default",0 ,0,100) diff --git a/driver/src/sick_scan_common.cpp b/driver/src/sick_scan_common.cpp index c02b489..8156f70 100644 --- a/driver/src/sick_scan_common.cpp +++ b/driver/src/sick_scan_common.cpp @@ -2780,7 +2780,7 @@ namespace sick_scan */ char *buffer_pos = (char *) receiveBuffer; char *dstart, *dend; - bool dumpDbg = true; // !!!!! + bool dumpDbg = false; bool dataToProcess = true; std::vector vang_vec; vang_vec.clear(); diff --git a/include/sick_scan/sick_generic_radar.h b/include/sick_scan/sick_generic_radar.h index e75a69c..5d5bee5 100644 --- a/include/sick_scan/sick_generic_radar.h +++ b/include/sick_scan/sick_generic_radar.h @@ -168,7 +168,7 @@ namespace sick_scan void simulateAsciiDatagramFromFile(unsigned char *receiveBuffer, int *actual_length, std::string filePattern); - bool emul; + bool emul = false; ros::NodeHandle nh_; ros::Publisher cloud_radar_rawtarget_pub_;