ROS Node¶
This node handles the communication of the Neobotix USBoard-USS5.
The USBoard-USS5 node has been tested with:
- ROS Kinetic on Ubuntu 16.04
- ROS Melodic on Ubuntu 18.04
- ROS Noetic on Ubuntu 20.04
Find the code of the ROS node at https://github.com/neobotix/neo_usboard_v2.
Installation¶
Clone the
neo_usboard_v2
repository into your catkin workspace source folder:cd your_catkin_workspace/src git clone https://github.com/neobotix/neo_usboard_v2.git
Clone
neo_msgs
into your catkin workspace source folder:git clone https://github.com/neobotix/neo_msgs.git
Fetch the submodules:
vnx-base
,pilot-base
andpilot-usboard
:cd neo_usboard_v2 git submodule update --init
Install
vnx-base
onto your system.ROS Kinetic:
sudo dpkg -i vnx-base/x86_64/vnx-base-1.9.3-x86_64-ubuntu-16.04.deb
ROS Melodic:
sudo dpkg -i vnx-base/x86_64/vnx-base-1.9.3-x86_64-ubuntu-18.04.deb
ROS Noetic:
sudo dpkg -i vnx-base/x86_64/vnx-base-1.9.3-x86_64-ubuntu-20.04.deb
Compile your workspace:
cd your_catkin_workspace catkin_make
Launch¶
In case of using CAN, the bus needs to be configured first:
sudo ip link set can0 down
sudo ip link set can0 type can bitrate 1000000
sudo ip link set can0 up
To launch the USBoard-USS5 ROS node use:
roslaunch neo_usboard_v2 neo_usboard_v2.launch
Parameters¶
The following parameters can be changed according to your needs in neo_usboard_v2.yaml
:
Parameter | Value | Note |
---|---|---|
can_id | 1024 | Needs to be a multiple of 32. |
can_device | None or can0 | |
serial_port | /dev/ttyUSB0 | |
can_baud_rate | 1000000 (bit/s) | Needs to match what is configured on the board. |
update_rate | 5 (Hz) | Relevant only in transmit mode “Request”, see USBoardV2 GUI. |
Note
If can_device
is set, the CAN bus will be used for communication,
otherwise the serial interface specified in serial_port
is used.
The following parameters can be changed from the parameter server once the ros node is executed.
Parameter | Value | Note |
---|---|---|
low_pass_gain | 1 | low pass filter gain (1 = no filtering) |
enable_analog_input | false | if to enable reading analog inputs |
enable_legacy_format | false | if to use old message format (when transmitting automatically) |
enable_can_termination | false | if to connect CAN bus termination resistance on the board |
relay_warn_blocked_invert | false | if to invert warn relay output when a sensor is blocked |
relay_alarm_blocked_invert | false | if to invert alarm relay output when a sensor is blocked |
active_sensors(0 to 15) | true | Active sensors from 1-16 |
warn_distance(0 to 15) | 100 cm | Warning distances of sensors 1-16 |
alarm_distance(0 to 15) | 30 cm | Alarm distances |
enable_transmission(0 to 4) | true | if the group transmits in continuous mode |
fire_interval_ms | 20 ms | time between pulses |
sending_sensor | 0 | index of the sensor which will send the pulse (cross echo mode) |
cross_echo_mode | false | if to enable cross echo mode |
Note
For setting the ros parameters from the application, it is advised to utilize the /usboard_v2/set_parameters service. If it is required to set the parameters from the command line, then please utilize the rosrun dynamic_reconfigure dynparam set param value command to configure it. Please use the command ros param list to see the available parameters.
Topics¶
The following ROS topics are available:
Name | Type |
---|---|
/usboard_v2/measurements | neo_msgs/msgs/USBoardV2 |
/usboard_v2/sensor1 | sensor_msgs/Range |
/usboard_v2/sensor2 | sensor_msgs/Range |
… | |
/usboard_v2/sensor16 | sensor_msgs/Range |
Multiple USBoards¶
In case of using multiple USBoard-USS5 simultaneously, it is possible to start multiple ROS nodes, one for each board.
Parameters¶
Each ROS node needs its own yaml configuration file, see for example
neo_usboard_v2.yaml
and neo_usboard_v2_1.yaml
in https://github.com/neobotix/neo_usboard_v2/tree/main/launch:
can_id: 1024
can_device: None
#can_device: can0
serial_port: /dev/ttyUSB0
can_baud_rate: 1000000
update_rate: 5
topic_path: /usboard_v2
can_id: 1056
can_device: None
#can_device: can1
serial_port: /dev/ttyUSB1
can_baud_rate: 1000000
update_rate: 5
topic_path: /usboard_v2_1
Note
CAN IDs need to be a multiple of 0x20
, ie. 32
in decimal.
Launching Multiple ROS Nodes¶
The standard launch file neo_usboard_v2.launch
contains an example on how to start another ROS node:
<?xml version="1.0"?>
<launch>
<!-- Load usboard_v2 params -->
<rosparam command="load" ns="usboard_v2" file="$(find neo_usboard_v2)/launch/neo_usboard_v2.yaml"/>
<!-- start usboard_v2 node -->
<node pkg="neo_usboard_v2" type="neo_usboard_v2" ns="usboard_v2" name="usboard_v2_node" respawn="false" output="screen"/>
<!-- Load usboard_v2 params for second board -->
<rosparam command="load" ns="usboard_v2_1" file="$(find neo_usboard_v2)/launch/neo_usboard_v2_1.yaml"/>
<!-- start usboard_v2 node for second board -->
<node pkg="neo_usboard_v2" type="neo_usboard_v2" ns="usboard_v2_1" name="usboard_v2_node_1" respawn="false" output="screen"/>
</launch>
Simply uncomment the second block to enable a second ROS node.
To launch all configured nodes:
roslaunch neo_usboard_v2 neo_usboard_v2.launch
Help¶
If you receive the error unable to connect to port /dev/ttyUSB0
, run
the following command:
sudo usermod -a -G dialout $USER
and restart your PC.