Skip to content

Commit 26281f0

Browse files
authored
Merge pull request #9 from SICKAG/feature/multiple_ols20
Merge feature/multiple_ols20
2 parents 8df7564 + 78ccbb4 commit 26281f0

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

45 files changed

+272
-123
lines changed

CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -303,6 +303,7 @@ install(FILES
303303
ols/SICK_OLS20_CO.eds
304304
ols/sick_line_guidance_ols10.yaml
305305
ols/sick_line_guidance_ols20.yaml
306+
ols/sick_line_guidance_ols20_twin.yaml
306307
test/cfg/sick_canopen_simu_cfg.xml
307308
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
308309
)

README.md

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ instructions on [doc/pcan-linux-installation.md](doc/pcan-linux-installation.md)
4444
Run the following script to install sick_line_guidance including all dependancies and packages required:
4545

4646
```bash
47-
source /opt/ros/melodic/setup.bash # currently ros distro melodic is supported
47+
source /opt/ros/noetic/setup.bash # currently ros distro melodic and noetic are supported
4848
cd ~ # or change to your project path
4949
mkdir -p catkin_ws/src/
5050
cd catkin_ws/src/
@@ -297,3 +297,18 @@ killall rosmaster # kill ros core
297297
```
298298

299299
Please note, that this kills all ros processes, not just those required for sick_line_guidance.
300+
301+
### "Debugging"
302+
303+
:question: Question: How can I run sick_line_guidance or ros_canopen in a debugger, e.g. gdb
304+
305+
:white_check_mark: Answer: A ros node can be started in gdb with prefix gdb, e.g.
306+
307+
```bash
308+
rosrun --prefix 'gdb -ex run --args' sick_line_guidance ...
309+
```
310+
311+
or with argument `launch-prefix="gdb -ex run - -args"` in the launchfile, e.g.
312+
```
313+
<node name="sick_line_guidance_can_chain_node" pkg="sick_line_guidance" type="sick_line_guidance_can_chain_node" launch-prefix="gdb -ex run - -args" output="screen" >
314+
```

doc/pcan-config/screenshot01.png

152 KB
Loading

doc/pcan-config/screenshot02.png

102 KB
Loading

doc/pcan-config/screenshot03.png

119 KB
Loading

doc/pcan-linux-installation.md

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -15,11 +15,12 @@ sudo dpkg --install pcanview-ncurses_0.8.7-0_amd64.deb
1515

1616
&nbsp; 2. If you're running ROS in a virtual machine, make sure the usb-port for the PCAN-USB-adapter is connected to your VM.
1717

18-
&nbsp; 3. Download and unzip peak-linux-driver-8.7.0.tar.gz from https://www.peak-system.com/linux/ or https://www.peak-system.com/fileadmin/media/linux/files/peak-linux-driver-8.7.0.tar.gz
18+
&nbsp; 3. Download and unzip peak-linux-driver-8.17.0.tar.gz from https://www.peak-system.com/quick/PCAN-Linux-Driver
19+
1920

2021
&nbsp; 4. Install the linux driver and required packages:
2122
```bash
22-
cd peak-linux-driver-8.7.0
23+
cd peak-linux-driver-8.17.0
2324
# install required packages
2425
sudo apt-get install can-utils
2526
sudo apt-get install gcc-multilib
@@ -46,18 +47,17 @@ ip -details link show can0 # should print some details about "can0" net device
4647
```
4748
Example output after successfull installation of a pcan usb adapter:
4849
```bash
49-
user@ubuntu-ros:~/peak-linux-driver-8.7.0$ ./driver/lspcan --all
50-
pcan version: 8.7.0
51-
pcanusb32 CAN1CAN1 8MHz 500k CLOSED - 0 0 0
52-
user@ubuntu-ros:~/peak-linux-driver-8.7.0$ tree /dev/pcan-usb
50+
user@ubuntu-ros:~/peak-linux-driver-8.17.0$ ./driver/lspcan --all
51+
pcanusb32 CAN1 - 8MHz 125k ACTIVE - 1969 0 0
52+
user@ubuntu-ros:~/peak-linux-driver-8.17.0$ tree /dev/pcan-usb
5353
/dev/pcan-usb
5454
├── 0
5555
│   └── can0 -> ../../pcanusb32
5656
└── devid=5 -> ../pcanusb32
57-
user@ubuntu-ros:~/peak-linux-driver-8.7.0$ ip -a link
57+
user@ubuntu-ros:~/peak-linux-driver-8.17.0$ ip -a link
5858
3: can0: <NOARP> mtu 16 qdisc noop state DOWN mode DEFAULT group default qlen 10
5959
link/can
60-
user@ubuntu-ros:~/peak-linux-driver-8.7.0$ ip -details link show can0
60+
user@ubuntu-ros:~/peak-linux-driver-8.17.0$ ip -details link show can0
6161
3: can0: <NOARP> mtu 16 qdisc noop state DOWN mode DEFAULT group default qlen 10
6262
link/can promiscuity 0
6363
can state STOPPED restart-ms 0

doc/sick_line_guidance_configuration.md

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -219,3 +219,14 @@ in the terminal. Example to write value 0x01 to object 2001sub5 (sensorFlipped):
219219
rosservice call /driver/set_object "{node: 'node1', object: '2001sub5', value: '0x01', cached: false}"
220220
```
221221
This command results in a can upload command using a SDO with object 2001sub5.
222+
223+
## Configuration of CAN node id
224+
225+
The node id of a CAN device can be configured e.b. with [PCAN-View](https://www.peak-system.com/PCAN-View.242.0.html):<br/>
226+
![screenshot01.png](pcan-config/screenshot01.png)<br/>
227+
![screenshot02.png](pcan-config/screenshot02.png)<br/>
228+
229+
## Installation and bus termination
230+
231+
The following screenshot shows the installation and bus termination for two OLS devices:<br/>
232+
![screenshot03.png](pcan-config/screenshot03.png)

include/sick_line_guidance/sick_line_guidance_can_cia401_subscriber.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -71,12 +71,14 @@ namespace sick_line_guidance
7171
* Constructor.
7272
* @param[in] nh ros::NodeHandle
7373
* @param[in] can_nodeid can id for canopen_chain_node, f.e. "node1"
74+
* @param[in] max_num_retries_after_sdo_error After SDO error, the query is repeated max. N times (default: N=2). If the SDO error persists, the can driver is shutdown and restarted.
75+
* @param[in] max_sdo_rate max. sdo query and publish rate
7476
* @param[in] ros_topic topic for ros messages, f.e. "mls" or "ols"
7577
* @param[in] ros_frameid frameid for ros messages, f.e. "mls_measurement_frame" or "ols_measurement_frame"
7678
* @param[in] initial_sensor_state initial sensor state (f.e. 0x07 for 3 detected lines, or (1 << 4) to indicate sensor error)
7779
* @param[in] subscribe_queue_size buffer size for ros messages
7880
*/
79-
CanCiA401Subscriber(ros::NodeHandle & nh, const std::string & can_nodeid, const std::string & ros_topic,
81+
CanCiA401Subscriber(ros::NodeHandle & nh, const std::string & can_nodeid, int max_num_retries_after_sdo_error, double max_sdo_rate, const std::string & ros_topic,
8082
const std::string & ros_frameid, int initial_sensor_state = 0, int subscribe_queue_size = 1);
8183

8284
/*

include/sick_line_guidance/sick_line_guidance_can_mls_subscriber.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -71,12 +71,14 @@ namespace sick_line_guidance
7171
* Constructor.
7272
* @param[in] nh ros::NodeHandle
7373
* @param[in] can_nodeid can id for canopen_chain_node, f.e. "node1"
74+
* @param[in] max_num_retries_after_sdo_error After SDO error, the query is repeated max. N times (default: N=2). If the SDO error persists, the can driver is shutdown and restarted.
75+
* @param[in] max_sdo_rate max. sdo query and publish rate
7476
* @param[in] ros_topic topic for ros messages, f.e. "mls" or "ols"
7577
* @param[in] ros_frameid frameid for ros messages, f.e. "mls_measurement_frame" or "ols_measurement_frame"
7678
* @param[in] initial_sensor_state initial sensor state (f.e. 0x07 for 3 detected lines, or (1 << 4) to indicate sensor error)
7779
* @param[in] subscribe_queue_size buffer size for ros messages
7880
*/
79-
CanMlsSubscriber(ros::NodeHandle & nh, const std::string & can_nodeid, const std::string & ros_topic,
81+
CanMlsSubscriber(ros::NodeHandle & nh, const std::string & can_nodeid, int max_num_retries_after_sdo_error, double max_sdo_rate, const std::string & ros_topic,
8082
const std::string & ros_frameid, int initial_sensor_state = 0, int subscribe_queue_size = 1);
8183

8284
/*

include/sick_line_guidance/sick_line_guidance_can_ols_subscriber.h

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -71,12 +71,14 @@ namespace sick_line_guidance
7171
* Constructor.
7272
* @param[in] nh ros::NodeHandle
7373
* @param[in] can_nodeid can id for canopen_chain_node, f.e. "node1"
74+
* @param[in] max_num_retries_after_sdo_error After SDO error, the query is repeated max. N times (default: N=2). If the SDO error persists, the can driver is shutdown and restarted.
75+
* @param[in] max_sdo_rate max. sdo query and publish rate
7476
* @param[in] ros_topic topic for ros messages, f.e. "mls" or "ols"
7577
* @param[in] ros_frameid frameid for ros messages, f.e. "mls_measurement_frame" or "ols_measurement_frame"
7678
* @param[in] initial_sensor_state initial sensor state (f.e. 0x07 for 3 detected lines, or (1 << 4) to indicate sensor error)
7779
* @param[in] subscribe_queue_size buffer size for ros messages
7880
*/
79-
CanOlsSubscriber(ros::NodeHandle & nh, const std::string & can_nodeid, const std::string & ros_topic,
81+
CanOlsSubscriber(ros::NodeHandle & nh, const std::string & can_nodeid, int max_num_retries_after_sdo_error, double max_sdo_rate, const std::string & ros_topic,
8082
const std::string & ros_frameid, int initial_sensor_state = 0, int subscribe_queue_size = 1);
8183

8284
/*
@@ -172,12 +174,14 @@ namespace sick_line_guidance
172174
* Constructor.
173175
* @param[in] nh ros::NodeHandle
174176
* @param[in] can_nodeid can id for canopen_chain_node, f.e. "node1"
177+
* @param[in] max_num_retries_after_sdo_error After SDO error, the query is repeated max. N times (default: N=2). If the SDO error persists, the can driver is shutdown and restarted.
178+
* @param[in] max_sdo_rate max. sdo query and publish rate
175179
* @param[in] ros_topic topic for ros messages, f.e. "mls" or "ols"
176180
* @param[in] ros_frameid frameid for ros messages, f.e. "mls_measurement_frame" or "ols_measurement_frame"
177181
* @param[in] initial_sensor_state initial sensor state (f.e. 0x07 for 3 detected lines, or (1 << 4) to indicate sensor error)
178182
* @param[in] subscribe_queue_size buffer size for ros messages
179183
*/
180-
CanOls10Subscriber(ros::NodeHandle & nh, const std::string & can_nodeid, const std::string & ros_topic,
184+
CanOls10Subscriber(ros::NodeHandle & nh, const std::string & can_nodeid, int max_num_retries_after_sdo_error, double max_sdo_rate, const std::string & ros_topic,
181185
const std::string & ros_frameid, int initial_sensor_state = 0, int subscribe_queue_size = 1);
182186

183187
}; // class CanOls10Subscriber
@@ -193,12 +197,14 @@ namespace sick_line_guidance
193197
* Constructor.
194198
* @param[in] nh ros::NodeHandle
195199
* @param[in] can_nodeid can id for canopen_chain_node, f.e. "node1"
200+
* @param[in] max_num_retries_after_sdo_error After SDO error, the query is repeated max. N times (default: N=2). If the SDO error persists, the can driver is shutdown and restarted.
201+
* @param[in] max_sdo_rate max. sdo query and publish rate
196202
* @param[in] ros_topic topic for ros messages, f.e. "mls" or "ols"
197203
* @param[in] ros_frameid frameid for ros messages, f.e. "mls_measurement_frame" or "ols_measurement_frame"
198204
* @param[in] initial_sensor_state initial sensor state (f.e. 0x07 for 3 detected lines, or (1 << 4) to indicate sensor error)
199205
* @param[in] subscribe_queue_size buffer size for ros messages
200206
*/
201-
CanOls20Subscriber(ros::NodeHandle & nh, const std::string & can_nodeid, const std::string & ros_topic,
207+
CanOls20Subscriber(ros::NodeHandle & nh, const std::string & can_nodeid, int max_num_retries_after_sdo_error, double max_sdo_rate, const std::string & ros_topic,
202208
const std::string & ros_frameid, int initial_sensor_state = 0, int subscribe_queue_size = 1);
203209

204210
}; // class CanOls20Subscriber

0 commit comments

Comments
 (0)