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

Commit

Permalink
Corrected angle shift parameter for LMS-4xxx
Browse files Browse the repository at this point in the history
  • Loading branch information
rostest committed Mar 3, 2022
1 parent 9f6b85d commit 9b77642
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 5 deletions.
4 changes: 4 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion driver/src/sick_generic_caller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <algorithm> // for std::min

Expand Down
8 changes: 4 additions & 4 deletions driver/src/sick_generic_parser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -346,7 +346,7 @@ namespace sick_scan
{
return this->maxEvalFields;
}

void ScannerBasicParam::setMaxEvalFields(int _maxEvalFields)
{
this->maxEvalFields = _maxEvalFields;
Expand Down Expand Up @@ -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
{
Expand Down Expand Up @@ -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;
Expand Down

0 comments on commit 9b77642

Please sign in to comment.