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

Commit

Permalink
Bugfix #158 (driver termination)
Browse files Browse the repository at this point in the history
Modified sopas startup sequence
  • Loading branch information
rostest committed Feb 28, 2022
1 parent 169f5bd commit 9f6b85d
Show file tree
Hide file tree
Showing 5 changed files with 51 additions and 17 deletions.
10 changes: 10 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,16 @@
Changelog for package sick_scan
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.12.0
-------------------
* bugfix #158 (driver terminates)
* modified SOPAS-startup sequence


1.11.0 (2021-07-13)
-------------------
* Added option min_intensity

1.10.1 (2021-03-18)
-------------------
* Update ipconfig.md
Expand Down
6 changes: 3 additions & 3 deletions driver/src/sick_generic_caller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,8 +120,8 @@
// 1.7.6: 2020-07-14: NAV310 handling optimized (angle calculation and compensation), barebone quaterion to euler
// 1.7.7: 2020-07-21: barebone quaterion to euler
#define SICK_GENERIC_MAJOR_VER "1"
#define SICK_GENERIC_MINOR_VER "10"
#define SICK_GENERIC_PATCH_LEVEL "1"
#define SICK_GENERIC_MINOR_VER "12"
#define SICK_GENERIC_PATCH_LEVEL "0"

#include <algorithm> // for std::min

Expand All @@ -131,7 +131,7 @@ std::string getVersionInfo();
/*!
\brief Startup routine - if called with no argmuments we assume debug session.
Set scanner name variable by parsing for "__name:=". This will be changed in the future
by setting a parameter. Calls mainGenericLaser after parsing.
by setting a parameter. Calls mainGenericLaser after parsing.

\param argc: Number of Arguments
\param argv: Argument variable
Expand Down
29 changes: 15 additions & 14 deletions driver/src/sick_scan_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2434,20 +2434,6 @@ namespace sick_scan
}
else
{
// initializing sequence for laserscanner
// is this device a TiM240????
// The TiM240 can not interpret CMD_START_MEASUREMENT
if (this->parser_->getCurrentParamPtr()->getScannerName().compare(SICK_SCANNER_TIM_240_NAME) == 0)
{
// the TiM240 operates directly in the ros coordinate system
// do nothing for a TiM240
}
else
{
startProtocolSequence.push_back(CMD_START_MEASUREMENT);
}
startProtocolSequence.push_back(CMD_RUN); // leave user level
startProtocolSequence.push_back(CMD_START_SCANDATA);

if (parser_->getCurrentParamPtr()->getUseEvalFields() == USE_EVAL_FIELD_TIM7XX_LOGIC || parser_->getCurrentParamPtr()->getUseEvalFields() == USE_EVAL_FIELD_LMS5XX_LOGIC)
{
Expand All @@ -2472,6 +2458,21 @@ namespace sick_scan
}
}

// initializing sequence for laserscanner
// is this device a TiM240????
// The TiM240 can not interpret CMD_START_MEASUREMENT
if (this->parser_->getCurrentParamPtr()->getScannerName().compare(SICK_SCANNER_TIM_240_NAME) == 0)
{
// the TiM240 operates directly in the ros coordinate system
// do nothing for a TiM240
}
else
{
startProtocolSequence.push_back(CMD_START_MEASUREMENT);
}
startProtocolSequence.push_back(CMD_RUN); // leave user level
startProtocolSequence.push_back(CMD_START_SCANDATA);

if (this->parser_->getCurrentParamPtr()->getNumberOfLayers() == 4) // MRS1104 - start IMU-Transfer
{
ros::NodeHandle tmp("~");
Expand Down
22 changes: 22 additions & 0 deletions test/scripts/readme.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
A simple lidar emulator for development and test purposes can be found in folder test/emulator. It implements a simple tcp server, which responds to binary cola messages and sends predefined LMDscandata to a tcp-client. The sick_scan driver can connect to the local test server instead of the lidar device for offline-tests.

To build the test server, activate cmake option `ENABLE_EMULATOR` in CMakeLists.txt and rebuild sick_scan. By default, option `ENABLE_EMULATOR` is switched off.

To run the test server, start sick_scan with one of the emulator launchfiles in test/emulator/launch, f.e.
```
roslaunch sick_scan emulator_01_default.launch # emulate TiM 7xx
roslaunch sick_scan emulator_lms1xx.launch # emulate LMS 1xx
roslaunch sick_scan emulator_lms5xx.launch # emulate LMS 5xx
```

Then start the driver with option hostname:=127.0.0.1, f.e.
```
roslaunch sick_scan sick_tim_7xx.launch hostname:=127.0.0.1
```

To visualize the emulation in rviz, run
```
rosrun rviz rviz -d ./src/sick_scan/test/emulator/config/rviz_emulator_cfg.rviz
```

Please note, that the test server does not emulate a lidar device in details. It simply replies predefined cola responses to the driver and sends LMDscandata from the json-files in test/emulator/scandata for diagnosis and offline-tests. Examples to build and run offline-tests can be found in folder test/scripts.
1 change: 1 addition & 0 deletions test/scripts/run_simu_tim7xx_tim7xxS.bash
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ for sick_scan_launch_file in sick_tim_7xx.launch sick_tim_7xxS.launch ; do
# rosservice call /sick_tim_7xx/ColaMsg "{request: 'sRN LIDinputstate'}" # response: "sRA LIDinputstate \\x00\\x00\\x00\\x00\\x00\\x00\\x01\\x00\\x00\\x00\\x00\\x00"
# rostopic echo "/sick_tim_7xxS/lferec" &
# rostopic echo "/sick_tim_7xxS/lidoutputstate" &
rostopic echo /diagnostics &

# Wait for 'q' or 'Q' to exit or until rviz is closed
while true ; do
Expand Down

0 comments on commit 9f6b85d

Please sign in to comment.