ROS-Node¶
Dieser Node übernimmt die Kommunikation des Neobotix USBoard-USS5.
Der USBoard-USS5-Node wurde getestet mit:
- ROS Kinetic auf Ubuntu 16.04
- ROS Melodic auf Ubuntu 18.04
- ROS Noetic auf Ubuntu 20.04
Sie finden den Quelltext der ROS-Node unter https://github.com/neobotix/neo_usboard_v2.
Installation¶
Klonen Sie das
neo_usboard_v2
-Repository in den source-Ordner Ihres Catkin Workspace:cd your_catkin_workspace/src git clone https://github.com/neobotix/neo_usboard_v2.git
Klonen Sie
neo_msgs
in den source-Ordner Ihres Catkin Workspace:git clone https://github.com/neobotix/neo_msgs.git
Laden Sie die benötigten Submodule:
vnx-base
,pilot-base
undpilot-usboard
:cd neo_usboard_v2 git submodule update --init
Installieren Sie
vnx-base
.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
Kompilieren Sie Ihren Workspace:
cd your_catkin_workspace catkin_make
Starten¶
Wenn CAN verwendet wird muss der Bus zuerst konfiguriert werden:
sudo ip link set can0 down
sudo ip link set can0 type can bitrate 1000000
sudo ip link set can0 up
Um den USBoard-USS5 ROS Node zu starten, verwenden Sie:
roslaunch neo_usboard_v2 neo_usboard_v2.launch
Parameter¶
Die folgenden Parameter können Sie in neo_usboard_v2.yaml
an Ihre Bedürfnisse anpassen:
Parameter | Wert | Hinweis |
---|---|---|
can_id | 1024 | Muss ein Vielfaches von 32 sein. |
can_device | Nichts oder can0 | |
serial_port | /dev/ttyUSB0 | |
can_baud_rate | 1000000 (bit/s) | Muss dem auf dem Board konfigurierten Wert entsprechen. |
update_rate | 5 (Hz) | Nur im „Request“-Sendemodus relevant. |
Bemerkung
Falls can_device
ein Wert zugewiesen wird, wird der CAN-Bus zur Kommunikation verwendet, andernfalls die mit serial_port
spezifizierte serielle Schnittstelle.
Die folgenden Parameter können über den Parameterserver gesetzt werden, während die ROS-Node läuft.
Parameter | Wert | Hinweis |
---|---|---|
low_pass_gain | 1 | Verstärkung des Tiefpassfilters (1 = kein Filter) |
enable_analog_input | false | Aanalogeingänge auslesen ein/aus |
enable_legacy_format | false | Altes Nachrichtenformat benutzen (bei automatischem Senden) |
enable_can_termination | false | CAN-Bus-Terminierung aktivieren |
relay_warn_blocked_invert | false | Warn-Relay invertieren, wenn ein Sensor blockiert ist |
relay_alarm_blocked_invert | false | Alarm-Relay invertieren, wenn ein Sensor blockiert ist |
active_sensors(0 to 15) | true | Aktive Sensoren |
warn_distance(0 to 15) | 100 cm | Warndistanz pro Sensor |
alarm_distance(0 to 15) | 30 cm | Alarmdistanz pro Sensor |
enable_transmission(0 to 4) | true | Gruppe in automatischem Modus aktiviert |
fire_interval_ms | 20 ms | Zeit zwischen zwei Impulsen |
sending_sensor | 0 | Index des Sensors der im Kreuzechomodus den Impuls sendet |
cross_echo_mode | false | Kreuzechomodus an/aus |
Bemerkung
Um die ROS-Parameter aus der Anwendung heraus zu setzen, empfehlen wir den Service /usboard_v2/set_parameters. Wenn ein Setzen über die Kommandozeile nötig ist, benutzen Sie den Befehl rosrun dynamic_reconfigure dynparam set param value. Nutzen Sie den Befehl ros param list, um die verfügbaren Parameter anzuzeigen.
Topics¶
Die folgenden ROS Topics sind verfügbar:
Name | Typ |
---|---|
/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 |
Mehrere USBoards¶
Im Fall von mehreren USBoard-USS5 ist es möglich, für jedes Board eine eigene ROS-Node zu starten.
Parameter¶
Jede ROS-Node braucht ihre eigene yaml-Konfigurationsdatei, sehen Sie zum Beispiel neo_usboard_v2.yaml
und 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
Bemerkung
CAN-IDs müssen ein Vielfaches von 0x20
sein, also 32
in Dezimalschreibweise.
Mehrere ROS-Nodes starten¶
Die Standard-Launchfile neo_uusboard_v2.launch
enthält ein Beispiel, um eine weitere ROS-Node zu starten:
<?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>
Entfernen Sie einfach die Kommentarzeichen beim zweiten Block und eine zweite ROS-Node zu starten.
Um alle konfigurierten Nodes zu starten:
roslaunch neo_usboard_v2 neo_usboard_v2.launch
Hilfe¶
Wenn Sie den Fehler unable to connect to port /dev/ttyUSB0
erhalten, führen Sie folgenden Befehl aus:
sudo usermod -a -G dialout $USER
und starten Sie Ihren PC neu.