ARS_40x package contains a driver for the Continental radar ARS_404 / ARS_408. The package also contains a ROS Wrapper for the driver.
Install can-utils to setup radar config
sudo apt-get install can-utils
candump can0 # Watch the raw data received once the peak CAN bus is installed and connected to Radar
Objects
cansend can0 200#F8000000089C0000 // Objects detection with all extended properties
Clusters
cansend can0 200#F8000000109C0000 // Clusters detection with all extended properties
Filter Selection
Maximum distance of objects detected 30 meters
cansend can0 202#8C0000012C
Minimum value of object RCS -10 dBm2
cansend can0 202#AE06800FFF
Minimum value of objects probability of existence 75%
cansend can0 202#C600030007
- socket_can
- [costmap_converter]
- [costmap_converter_msgs]
- [visualization_msgs]
- [perception_msgs]
colcon build --symlink-install --packages-up-to ars_40x
- Enable CAN interface
sudo ip link set down can0 # If already enabled
sudo ip link set can0 up type can bitrate 500000
- Check if the radar is connected
candump can0
- Run the driver
roslaunch ars_40x ars_40x.launch visualize:=true obstacle_array:=true
There are arugments available for the launch file:
- visualize (default:"true") : Launches RViz to display the clusters/obstacles as markers.
- obstacle_array (default:"false") : Launches ars_40x_obstacle_array node which publishes obstacles as geometry_msgs/Polygon
Message | Type | Description | Message Box |
---|---|---|---|
/radar_status | ars_40x/RadarStatus | Describe the radar configuration | 0x201 |
/ars_40x/clusters | ars_40x/ClusterList | Raw clusters data from radar | 0x600, 0x701 |
/ars_40x/objects | ars_40x/ObjectList | Raw objects data from radar | 0x60A, 0x60B, 0x60C, 0x60D |
/visualize_clusters | visualization_msgs/MarkerArray | Clusters markers for RViz visualization | - |
/visualize_objects | visualization_msgs/MarkerArray | Object markers for RViz visualization | - |
Message | Type | Description | Message Box |
---|---|---|---|
/odom | nav_msgs/Odometry | Velocity and accleration information | 0x300, 0x301 |
The following services are available for configuring the radar options available in 0x200
Services |
---|
/set_ctrl_relay_cfg |
/set_max_distance |
/set_output_type |
/set_radar_power |
/set_rcs_threshold |
/set_send_ext_info |
/set_send_quality |
/set_sensor_id |
/set_sort_index |
/set_store_in_nvm |
To make the nodes standalone and create a custom can message to change the radar configuration, a ROS service is created to change the radar configuration.
ros2 service call /set_max_distance perception_msgs/srv/MaxDistance "{max_distance: 160.0}"
The command follow the ros2 service call format
ros2 service call /<service_name> <service_type> "{<service_field>: <value>}"