diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 07a74b7..f0cf3e3 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,10 @@ Changelog for package sick_scan ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.12.1 +------------------- +* Corrected angle shift parameter for LMS-4xxx + 1.12.0 ------------------- * bugfix #158 (driver terminates) diff --git a/driver/src/sick_generic_caller.cpp b/driver/src/sick_generic_caller.cpp index e75e489..f04093a 100644 --- a/driver/src/sick_generic_caller.cpp +++ b/driver/src/sick_generic_caller.cpp @@ -121,7 +121,7 @@ // 1.7.7: 2020-07-21: barebone quaterion to euler #define SICK_GENERIC_MAJOR_VER "1" #define SICK_GENERIC_MINOR_VER "12" -#define SICK_GENERIC_PATCH_LEVEL "0" +#define SICK_GENERIC_PATCH_LEVEL "1" #include // for std::min diff --git a/driver/src/sick_generic_parser.cpp b/driver/src/sick_generic_parser.cpp index f18e109..fa7f5e8 100644 --- a/driver/src/sick_generic_parser.cpp +++ b/driver/src/sick_generic_parser.cpp @@ -346,7 +346,7 @@ namespace sick_scan { return this->maxEvalFields; } - + void ScannerBasicParam::setMaxEvalFields(int _maxEvalFields) { this->maxEvalFields = _maxEvalFields; @@ -514,7 +514,7 @@ namespace sick_scan basicParams[i].setScanMirroredAndShifted(false); basicParams[i].setUseEvalFields(EVAL_FIELD_UNSUPPORTED); basicParams[i].setMaxEvalFields(0); - basicParams[i].setScanAngleShift(0); + basicParams[i].setScanAngleShift(-M_PI/2); } if (basicParams[i].getScannerName().compare(SICK_SCANNER_TIM_7XX_NAME) == 0) // TIM_7xx - 1 Layer Scanner { @@ -848,10 +848,10 @@ namespace sick_scan sensor_msgs::LaserScan &msg, int &numEchos, int &echoMask) { // echoMask introduced to get a workaround for cfg bug using MRS1104 - // ros::NodeHandle tmpParam("~"); + // ros::NodeHandle tmpParam("~"); bool dumpData = false; int verboseLevel = 0; - // tmpParam.getParam("verboseLevel", verboseLevel); + // tmpParam.getParam("verboseLevel", verboseLevel); int HEADER_FIELDS = 32; char *cur_field;