Show EOL distros: 

Package Summary

ROS drivers (interfaces) and nodes for Ainstein radars.

  • Maintainer status: maintained
  • Maintainer: Nick Rotella <nick.rotella AT ainstein DOT ai>
  • Author: Nick Rotella
  • License: BSD

Package Summary

ROS drivers (interfaces) and nodes for Ainstein radars.

  • Maintainer status: maintained
  • Maintainer: Nick Rotella <nick.rotella AT ainstein DOT ai>
  • Author: Nick Rotella
  • License: BSD

Overview

ROS drivers (interfaces) and nodes for Ainstein radars.

Devices Supported

  • O79 (added Mar. 2020)
  • T79 with normal (ZOI) firmware (added Oct. 2019)
  • K77/T79 with 4+1 (BSD) firmware (added Mar. 2019)
  • SRD-D1 (added Mar. 2019)

Nodes (and Nodelets)

o79_udp_node

Runs the O79 driver to read Ethernet (UDP) data, parse it and publish radar detections. The O79 imaging radar outputs both raw detections (point cloud) and tracked detections (objects) via an onboard multi-object tracking algorithm. The tracking algorithm can be run in either spherical or Cartesian coordinates; the published topics change accordingly. See the O-79 device manual for more information.

Published Topics

~targets/raw (ainstein_radar_msgs/RadarTargetArray)
  • Raw radar targets/detections, post-CFAR (point cloud)
~targets/tracked (ainstein_radar_msgs/RadarTargetArray)
  • Tracked radar targets/detections, post-CFAR and object tracking filter (objects)
~cloud/raw (sensor_msgs/PointCloud2) ~cloud/tracked (sensor_msgs/PointCloud2) ~boxes (ainstein_radar_msgs/BoundingBoxArray)
  • 3D bounding boxes corresponding to track objects' extents
~poses (geometry_msgs/PoseArray)
  • Cartesian tracking filter tracked object poses (3D position + 3D orientation aligned with tracked velocity)
~velocities (ainstein_radar_msgs/TwistArray)
  • Cartesian tracking filter tracked object velocities (3D position + 3D orientation aligned with tracked velocity)

Parameters

~frame_id (string, default: "map")
  • The frame attached to the radar sensor.
~host_ip (string, default: "10.0.0.75")
  • The host machine's static IP address.
~host_port (int, default: 1024)
  • The host machine's Ethernet port, to which the radar sends data.
~radar_ip (string, default: "10.0.0.10")
  • The radar's IP address, configured and stored on the device.
~radar_port (int, default: 7)
  • The radar's Ethernet port from which data is sent, configured and stored on the device.
~publish_raw_cloud (bool, default: false)
  • Sets whether to publish the raw targets as a PointCloud2 message.
~publish_tracked_cloud (bool, default: false)
  • Sets whether to publish the tracked targets as a PointCloud2 message.

o79_can_node

Runs the O79 driver to read CAN data, parse it and publish radar detections. The O79 imaging radar outputs both raw detections (point cloud) and tracked detections (objects) via an onboard multi-object tracking algorithm. The tracking algorithm can be run in either spherical or Cartesian coordinates; the published topics change accordingly. See the O-79 device manual for more information.

Published Topics

~targets/raw (ainstein_radar_msgs/RadarTargetArray)
  • Published raw radar detections (point cloud)
~targets/tracked (ainstein_radar_msgs/RadarTargetArray)
  • Published tracked radar detections (objects)

Parameters

~frame_id (string, default: "map")
  • The frame attached to the radar sensor.
~can_id (string, default: "0x18FFB24D")
  • The ID which CAN messages are published from on the bus.

t79_node

Runs the T79 driver to read CAN data, parse it and publish radar detections.

Subscribed Topics

received_messages (can_msgs/Frame)
  • Raw CAN frames sent from radar

Published Topics

~targets/raw (ainstein_radar_msgs/RadarTargetArray)
  • Published raw radar detections (targets)
~targets/tracked (ainstein_radar_msgs/RadarTargetArray)
  • Published tracked radar detections (targets)

Parameters

~frame_id (string, default: "map")
  • The frame attached to the radar sensor.
~can_id (int, default: 0)
  • The radar's CAN ID number (0-9), configured and stored on the device.
~min_range (float, default: 0.0)
  • Minimum range for output detections, in meters (DYNAMICALLY RECONFIGURABLE).
~max_range (float, default: 100.0)
  • Maximum range for output detections, in meters (DYNAMICALLY RECONFIGURABLE).
~min_angle (float, default: 60.0)
  • Minimum azimuth angle for output detections, in positive degrees (DYNAMICALLY RECONFIGURABLE).
~max_angle (float, default: 60.0)
  • Maximum azimuth angle for output detections, in positive degrees (DYNAMICALLY RECONFIGURABLE).

t79_bsd_node

Runs the driver for a radar in the 4+1 configuration (corner T-79's + front-facing K-77) to read CAN data, parse it and publish radar detections and BSD-related "alarms" (in the case of rear T-79's). The same node is used for K-77 and corner T-79's by changing the "radar_type" parameter, as the intent is for all five radars to be used on a car simultaneously for collision awareness.

Subscribed Topics

received_messages (can_msgs/Frame)
  • Raw CAN frames sent from radar

Published Topics

~targets/raw (ainstein_radar_msgs/RadarTargetArray)
  • Published raw radar detections (targets)
~targets/tracked (ainstein_radar_msgs/RadarTargetArray)
  • Published tracked radar detections (targets)

Parameters

~frame_id (string, default: "map")
  • The frame attached to the radar sensor.
~radar_type (int, default: 0)
  • The radar's type in the 4+1 configuration, set in firmware. Options are 0 (K-77), 1 (front-left T-79), 2 (front-right T-79), 3 (rear-left T-79), or 4 (rear-right T-79).

srd_d1_node

Runs the SRD-D1 driver to read UART data, parse it and publish radar detections.

Published Topics

~targets/raw (ainstein_radar_msgs/RadarTargetArray)
  • Published raw radar detections (targets)

Parameters

~frame_id (string, default: "map")
  • The frame attached to the radar sensor.
~device_id (string, default: "/dev/ttyUSB0")
  • The name of the serial interface to the radar. Assumes a serial-to-USB converter is used by default.
~firmware_version (strind, default: "old")
  • Specifies the firmware version, either "old" or "new". This changes the baudrate and message definitions, see code for details.

Usage

T79+BSD and/or K77

To configure the radar type prior to testing, use the provided t79_bsd_config.sh script which depends on can-utils. Using eg. candump can0 is also useful debugging tool to monitor CAN traffic on the SocketCAN interface.

These CAN radars require a socketcan_bridge node publishing CAN frames to the /received_messages ROS topic (see the launch file below for an example). This package can be installed with:

bash sudo apt install ros-kinetic-socketcan-bridge

K79

The file k79_node.cpp implements a ROS node using the RadarInterfaceK79 interface class to create a UDP socket bound to the host IP address and port (which must match the radar's configuration), launch a thread to read and publish data to the RadarData message type.

The python script k79_gui.py can be used to configure the network parameters and flash new firmware. See the tutorials for more information.

Launch Files

The easiest way to get started with any particular radar is to use the corresponding example launch files.

Wiki: ainstein_radar_drivers (last edited 2020-12-23 01:28:10 by AinsteinAi)