(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Getting started with the O79 imaging radar

Description: Guide for setup and initial testing of O-79 with ROS

Tutorial Level: BEGINNER

Connecting the radar

Connect the radar cable to the radar and supply 12V DC power to the red (DC) and orange (ignition) wires, with black as ground. The nominal current draw is roughly 0.3A when connected but not transmitting detections. During operation, the current can be as high as 1.0A depending on number of detections.

Setting up your computer to communicate with the radar

The O-79 radar communicates data via CAN and/or Ethernet (UDP); configuration can currently be done in Ethernet (TCP) mode only. In this section, we'll describe how to set up your computer for each of these communication modes.

CAN communication

The radar communicates on CAN with a baudrate of 250Kbit/s. If you don't have a hardware CAN bus (for example on an NVIDIA TX2 using a CAN transceiver) then you'll need an adapter like the PCAN-USB adapter and associated drivers.

Once the requisite driver(s) have been installed and loaded (eg via modprobe) you can run:

sudo ip link set can0 down && sudo ip link set can0 type can bitrate 250000 && sudo ip link set can0 up

to set up the CAN bus with the correct speed. When the radar is powered and outputting CAN data, you should be able to monitor it with candump can0 if your bus is set up correctly.

Ethernet communication

By default, the radar transmits data packets via UDP to IP address 10.0.0.75, however this (and other network parameters) can be reconfigured at a later step in this tutorial. The network interface for communicating with the radar can be set up either graphically with the Gnome network manager GUI or by modifying the system networking files; see below for both approaches.

Network configuration via Gnome GUI

This process varies slightly depending on the version of Ubuntu being used, but the settings remain the same. Choose to add a new wired interface in your network interface settings by navigating to Settings > Network and clicking the + icon next to Wired (Ubuntu 18.04) or by choosing Edit Connections... in the dropdown menu from the network icon in the upper toolbar and clicking the Add button.

Name the connection and choose the Ethernet device to be used from the dropdown list (this will vary between computers, on the TX2 it is eth0. Be careful to choose the correct interface if your machine has more than one Ethernet port):

K79_network_config1.png

Then, switch to the IPv4 Settings tab and set connection method to manual (static) with the following properties:

K79_network_config2.png

Click Save and close the network manager windows, then connect to the network by choosing it from the list of valid connections. You should now be able to open a terminal and ping 10.0.0.10 and see the following:

K79_ping.png

Network configuration via interfaces file

For an embedded application, you likely wish to configure different networking interfaces (eg CAN, Ethernet, WiFi) manually at boot via the /etc/network/interfaces file. To do this, edit the file and add the following, replacing eth0 with the name of your Ethernet interface:

auto eth0
iface eth0 inet static
address 10.0.0.75
netmask 255.255.255.0
gateway 0.0.0.0

After adding this to /etc/network/interfaces, either reboot the system or reload the interface with

sudo ifdown eth0 && sudo ip addr flush eth0 && sudo ifup eth0

Then confirm that ping 10.0.0.10 works as expected.

Installing the ainstein_radar ROS packages

Once ROS is installed and you've gone through some of the basic usage tutorials, you can clone and build the ainstein_radar package from GitHub:

First, navigate to the source directory of your catkin workspace, typically located at ~/catkin_ws/, with:

cd ~/catkin_ws/src/

Now, clone the package:

git clone https://github.com/AinsteinAI/ainstein_radar.git

Once the package has been cloned to the source directory, back out to the catkin workspace root directory and update your dependencies for the new package:

cd ..
rosdep install --from-paths src --ignore-src --rosdistro=DISTRONAME

where DISTRONAME should be changed to the ROS version you installed. This may prompt you to agree to install dependencies. Now, you can build all the packages (including the new one) by first re-sourcing the environment setup script and using catkin_make, first building the messages package (all other packages depend on it; this is a temporary workaround) and then the full package:

source devel/setup.bash
catkin_make --pkg ainstein_radar_msgs
catkin_make

Open a new terminal and try roscd ainstein_radar and you should be brought to the root of the ainstein_radar metapackage, likely at ~/catkin_ws/src/ainstein_radar/ainstein_radar. You're now ready to use the nodes provided by the Ainstein packages!

Running the ROS node

Once the radar responds to ping commands, you can attempt to run the O79 ROS node. This is most easily done via an accompanying launch file in ainstein_radar_drivers:

<launch>

  <!-- Run the O79 CAN node for CAN output -->
  <node name="socketcan_bridge" pkg="socketcan_bridge" type="socketcan_bridge_node"  required="true" >
    <param name="can_device" value="can0" />
  </node>
  <node name="o79_can" pkg="ainstein_radar_drivers" type="o79_can_node" required="true" output="screen" >
    <param name="can_id" value="0x18FFB24D" />
  </node>

  <!-- Run the O79 UDP node for Ethernet output -->
  <node name="o79_udp" pkg="ainstein_radar_drivers" type="o79_udp_node" output="screen" required="true" >
    <param name="host_ip" value="10.0.0.75" />
    <param name="host_port" value="1024" />
    <param name="radar_ip" value="10.0.0.10" />
    <param name="radar_port" value="7" />
  </node>
  
</launch>

This will run both a o79_udp_node for Ethernet communication and a o79_can_node for CAN communication; edit the launch file before running depending on the communication mode you've enabled and network parameters chosen (if not default).

By default, as of this writing, the radar does not output UDP data automatically. To start UDP raw and/or tracked output, issue the following commands:

echo "raw" > /dev/udp/10.0.0.10/7
echo "tracked" > /dev/udp/10.0.0.10/7

Once data is being output over CAN (check with candump can0) and/or UDP (check using Wireshark), run the launch file:

roslaunch ainstein_radar_drivers o79_node.launch

Once the node is running, you should be able to see data streaming with rostopic echo as below (for example, tracked CAN objects):

rostopic echo /o79_can/targets/tracked

O-79 coordinate frame

The coordinate frame of the O79 (and other Ainstein radars) is defined as follows:

  1. The sensor coordinate frame is x-forward, y-left and z-up, with positive azimuth angle measured around positive z-axis.
  2. Range is the distance in meters from the radar to the detection along the axis defined by the azimuth angle.
  3. Speed is measured in meters per second along the axis defined by the azimuth angle, with positive speed integrating to positive range (moving away from the sensor) and vice versa.

By default, radar data is published in the "map" frame for simplicity, however the frame_id node parameter allows changing the data frame in ROS.

Viewing data in RViz

Once the ROS node is running (check rosnode list to be sure), you can open RViz and view the data using the RViz plugins for radar data (built/installed as part of the ainstein_radar package). To open RViz, in a new terminal run:

rosrun rviz rviz # or just rviz should work

Click the Add button at the bottom of the Displays panel (on the left by default). In the window that opens, select to add a display "By topic". You should now see a new display for the RadarTargetArray message type in the Displays panel on the left, and red markers indicating radar detections (targets) similar to below:

K79_rviz_data_small.png

Wiki: ainstein_radar/Tutorials/Getting started with the O79 imaging radar (last edited 2020-11-16 15:57:21 by AinsteinAi)