Skip to content

Commit

Permalink
Merge pull request #9 from SICKAG/feature/multiple_ols20
Browse files Browse the repository at this point in the history
Merge feature/multiple_ols20
  • Loading branch information
rostest authored Mar 26, 2024
2 parents 8df7564 + 78ccbb4 commit 26281f0
Show file tree
Hide file tree
Showing 45 changed files with 272 additions and 123 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -303,6 +303,7 @@ install(FILES
ols/SICK_OLS20_CO.eds
ols/sick_line_guidance_ols10.yaml
ols/sick_line_guidance_ols20.yaml
ols/sick_line_guidance_ols20_twin.yaml
test/cfg/sick_canopen_simu_cfg.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
Expand Down
17 changes: 16 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ instructions on [doc/pcan-linux-installation.md](doc/pcan-linux-installation.md)
Run the following script to install sick_line_guidance including all dependancies and packages required:

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

Please note, that this kills all ros processes, not just those required for sick_line_guidance.

### "Debugging"

:question: Question: How can I run sick_line_guidance or ros_canopen in a debugger, e.g. gdb

:white_check_mark: Answer: A ros node can be started in gdb with prefix gdb, e.g.

```bash
rosrun --prefix 'gdb -ex run --args' sick_line_guidance ...
```

or with argument `launch-prefix="gdb -ex run - -args"` in the launchfile, e.g.
```
<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" >
```
Binary file added doc/pcan-config/screenshot01.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/pcan-config/screenshot02.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/pcan-config/screenshot03.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
16 changes: 8 additions & 8 deletions doc/pcan-linux-installation.md
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,12 @@ sudo dpkg --install pcanview-ncurses_0.8.7-0_amd64.deb

&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.

&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
&nbsp; 3. Download and unzip peak-linux-driver-8.17.0.tar.gz from https://www.peak-system.com/quick/PCAN-Linux-Driver


&nbsp; 4. Install the linux driver and required packages:
```bash
cd peak-linux-driver-8.7.0
cd peak-linux-driver-8.17.0
# install required packages
sudo apt-get install can-utils
sudo apt-get install gcc-multilib
Expand All @@ -46,18 +47,17 @@ ip -details link show can0 # should print some details about "can0" net device
```
Example output after successfull installation of a pcan usb adapter:
```bash
user@ubuntu-ros:~/peak-linux-driver-8.7.0$ ./driver/lspcan --all
pcan version: 8.7.0
pcanusb32 CAN1CAN1 8MHz 500k CLOSED - 0 0 0
user@ubuntu-ros:~/peak-linux-driver-8.7.0$ tree /dev/pcan-usb
user@ubuntu-ros:~/peak-linux-driver-8.17.0$ ./driver/lspcan --all
pcanusb32 CAN1 - 8MHz 125k ACTIVE - 1969 0 0
user@ubuntu-ros:~/peak-linux-driver-8.17.0$ tree /dev/pcan-usb
/dev/pcan-usb
├── 0
│   └── can0 -> ../../pcanusb32
└── devid=5 -> ../pcanusb32
user@ubuntu-ros:~/peak-linux-driver-8.7.0$ ip -a link
user@ubuntu-ros:~/peak-linux-driver-8.17.0$ ip -a link
3: can0: <NOARP> mtu 16 qdisc noop state DOWN mode DEFAULT group default qlen 10
link/can
user@ubuntu-ros:~/peak-linux-driver-8.7.0$ ip -details link show can0
user@ubuntu-ros:~/peak-linux-driver-8.17.0$ ip -details link show can0
3: can0: <NOARP> mtu 16 qdisc noop state DOWN mode DEFAULT group default qlen 10
link/can promiscuity 0
can state STOPPED restart-ms 0
Expand Down
11 changes: 11 additions & 0 deletions doc/sick_line_guidance_configuration.md
Original file line number Diff line number Diff line change
Expand Up @@ -219,3 +219,14 @@ in the terminal. Example to write value 0x01 to object 2001sub5 (sensorFlipped):
rosservice call /driver/set_object "{node: 'node1', object: '2001sub5', value: '0x01', cached: false}"
```
This command results in a can upload command using a SDO with object 2001sub5.

## Configuration of CAN node id

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/>
![screenshot01.png](pcan-config/screenshot01.png)<br/>
![screenshot02.png](pcan-config/screenshot02.png)<br/>

## Installation and bus termination

The following screenshot shows the installation and bus termination for two OLS devices:<br/>
![screenshot03.png](pcan-config/screenshot03.png)
Original file line number Diff line number Diff line change
Expand Up @@ -71,12 +71,14 @@ namespace sick_line_guidance
* Constructor.
* @param[in] nh ros::NodeHandle
* @param[in] can_nodeid can id for canopen_chain_node, f.e. "node1"
* @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.
* @param[in] max_sdo_rate max. sdo query and publish rate
* @param[in] ros_topic topic for ros messages, f.e. "mls" or "ols"
* @param[in] ros_frameid frameid for ros messages, f.e. "mls_measurement_frame" or "ols_measurement_frame"
* @param[in] initial_sensor_state initial sensor state (f.e. 0x07 for 3 detected lines, or (1 << 4) to indicate sensor error)
* @param[in] subscribe_queue_size buffer size for ros messages
*/
CanCiA401Subscriber(ros::NodeHandle & nh, const std::string & can_nodeid, const std::string & ros_topic,
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,
const std::string & ros_frameid, int initial_sensor_state = 0, int subscribe_queue_size = 1);

/*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,12 +71,14 @@ namespace sick_line_guidance
* Constructor.
* @param[in] nh ros::NodeHandle
* @param[in] can_nodeid can id for canopen_chain_node, f.e. "node1"
* @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.
* @param[in] max_sdo_rate max. sdo query and publish rate
* @param[in] ros_topic topic for ros messages, f.e. "mls" or "ols"
* @param[in] ros_frameid frameid for ros messages, f.e. "mls_measurement_frame" or "ols_measurement_frame"
* @param[in] initial_sensor_state initial sensor state (f.e. 0x07 for 3 detected lines, or (1 << 4) to indicate sensor error)
* @param[in] subscribe_queue_size buffer size for ros messages
*/
CanMlsSubscriber(ros::NodeHandle & nh, const std::string & can_nodeid, const std::string & ros_topic,
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,
const std::string & ros_frameid, int initial_sensor_state = 0, int subscribe_queue_size = 1);

/*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,12 +71,14 @@ namespace sick_line_guidance
* Constructor.
* @param[in] nh ros::NodeHandle
* @param[in] can_nodeid can id for canopen_chain_node, f.e. "node1"
* @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.
* @param[in] max_sdo_rate max. sdo query and publish rate
* @param[in] ros_topic topic for ros messages, f.e. "mls" or "ols"
* @param[in] ros_frameid frameid for ros messages, f.e. "mls_measurement_frame" or "ols_measurement_frame"
* @param[in] initial_sensor_state initial sensor state (f.e. 0x07 for 3 detected lines, or (1 << 4) to indicate sensor error)
* @param[in] subscribe_queue_size buffer size for ros messages
*/
CanOlsSubscriber(ros::NodeHandle & nh, const std::string & can_nodeid, const std::string & ros_topic,
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,
const std::string & ros_frameid, int initial_sensor_state = 0, int subscribe_queue_size = 1);

/*
Expand Down Expand Up @@ -172,12 +174,14 @@ namespace sick_line_guidance
* Constructor.
* @param[in] nh ros::NodeHandle
* @param[in] can_nodeid can id for canopen_chain_node, f.e. "node1"
* @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.
* @param[in] max_sdo_rate max. sdo query and publish rate
* @param[in] ros_topic topic for ros messages, f.e. "mls" or "ols"
* @param[in] ros_frameid frameid for ros messages, f.e. "mls_measurement_frame" or "ols_measurement_frame"
* @param[in] initial_sensor_state initial sensor state (f.e. 0x07 for 3 detected lines, or (1 << 4) to indicate sensor error)
* @param[in] subscribe_queue_size buffer size for ros messages
*/
CanOls10Subscriber(ros::NodeHandle & nh, const std::string & can_nodeid, const std::string & ros_topic,
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,
const std::string & ros_frameid, int initial_sensor_state = 0, int subscribe_queue_size = 1);

}; // class CanOls10Subscriber
Expand All @@ -193,12 +197,14 @@ namespace sick_line_guidance
* Constructor.
* @param[in] nh ros::NodeHandle
* @param[in] can_nodeid can id for canopen_chain_node, f.e. "node1"
* @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.
* @param[in] max_sdo_rate max. sdo query and publish rate
* @param[in] ros_topic topic for ros messages, f.e. "mls" or "ols"
* @param[in] ros_frameid frameid for ros messages, f.e. "mls_measurement_frame" or "ols_measurement_frame"
* @param[in] initial_sensor_state initial sensor state (f.e. 0x07 for 3 detected lines, or (1 << 4) to indicate sensor error)
* @param[in] subscribe_queue_size buffer size for ros messages
*/
CanOls20Subscriber(ros::NodeHandle & nh, const std::string & can_nodeid, const std::string & ros_topic,
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,
const std::string & ros_frameid, int initial_sensor_state = 0, int subscribe_queue_size = 1);

}; // class CanOls20Subscriber
Expand Down
Loading

0 comments on commit 26281f0

Please sign in to comment.