Skip to content
This repository has been archived by the owner on Mar 8, 2023. It is now read-only.

Commit

Permalink
Merge remote-tracking branch 'origin/master'
Browse files Browse the repository at this point in the history
  • Loading branch information
michael1309 committed Jul 2, 2020
2 parents eff50f0 + 070bc38 commit df37ed2
Show file tree
Hide file tree
Showing 3 changed files with 2 additions and 3 deletions.
1 change: 0 additions & 1 deletion cfg/SickScan.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion driver/src/sick_scan_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<float> vang_vec;
vang_vec.clear();
Expand Down
2 changes: 1 addition & 1 deletion include/sick_scan/sick_generic_radar.h
Original file line number Diff line number Diff line change
Expand Up @@ -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_;
Expand Down

0 comments on commit df37ed2

Please sign in to comment.