Radar Data Analysis

From Waveshare Wiki
Jump to: navigation, search

JetBot ROS AI Kit Advanced Tutorial Directory

Step 1: Start the radar and enable its node

  • Start the radar and enter the following command on the robot to enable the radar node:
roslaunch jetbot_pro lidar.launch #Start the radar node
  • Note: If an error occurs when enabling the radar node, please CTRL+C to close the node, and then enter "reboot" to the robot.
  • Enter the following command on the virtual machine to open the RVIZ graphics tool.
 rosrun rviz rviz  
  • In the graphical interface, please add the LaserScan component, select the /scan topic for the Topic, select base_footprint for the Fixed Frame, and add the TF component; the red points in the image are the points scanned by the radar.

Radar Data Analysis.png

  • TF displays two coordinates, where base_footprint is the robot chassis coordinates, laser_frame is the radar coordinates, the radar coordinates and the chassis coordinates are opposite.

Radar Data Analysis02.png

Step 2: Rdar Data Analysis

  • Run the following command to check the /scan data type of the radar topic.
 rostopic type /scan    

Radar Data Analysis03.png

  • As shown on the figure above, the output type is sensor_msgs/LaserScan, and you can input the following command to check the detailed message structure of LaserScan.
 rosmsg show sensor_msgs/LaserScan  

Radar Data Analysis05.png

  • Among which:
std_msgs/Header header # Header is also a structure, including seq, stamp, frame_id
      uint32 seq # refers to the id that increases in scan order
      time stamp # stamp contains the time to start the scan and the time difference from the start of the scan. Note that the scan starts counterclockwise from the front.
string frame_id # frame_id is the name of the scanned reference system, which is very important in ROS. The message will be bound to tf to read the data
                                           
float32 angle_min # The angle at which to start scanning (rad)
float32 angle_max # The angle at which to end the scan (rad)
float32 angle_increment # The angle to increase with each scan (rad)

float32 time_increment # measurement interval (second)
float32 scan_time # scan interval (second)

float32 range_min # Minimum distance (m)
float32 range_max # maximum distance (m)

float32[] ranges # distance array (m), the length of the array is equal to the scan angle divided by each increment of the angle
float32[] intensities # device-dependent, intensity array, the same length as ranges
  • Enter the following command to check the /scan data of the radar topic.
rostopic echo /scan  

Radar Data Analysis04.png

  • Among the data, it can be found that the scanning angle is -3.14 ~ 3.14, that is, a circle of 360 degrees; the radar scanning distance range is 0.15m~12M. The ranges data is the distance data of each angle, and the length of the array is about (angle_max-angle_min)/angle_increment.
  • The A1 radar angle is shown in the figure below. The first data angle of ranges is 0 degrees in the figure (that is, directly in front of the robot), and the last data is 360 degrees.

Radar Data Analysis06.png

Step 3: Radar data filtering

  • From the above steps, we know the data format and radar data information sent by the radar, so we can choose to filter the unwanted parts.
  • [Note: Please close the radar node first, otherwise an error will occur if you start the radar node multiple times.]
  • Enter the following command on the robot side to start the radar filter node.
 roslaunch jetbot_pro laser_filter.launch #Start the radar filter node
  • Run the following command on the virtual machine side to open the RVIZ graphical tool interface.
 rosrun rviz rviz
  • Add LaserScan component, Topic select /filteredscan topic, Fixed Frame select base_footprint; add TF component to display the coordinates of the robot chassis; the red points in the image are the points scanned by the radar. At this time, it can be found that the radar data is only the first half, and the general data behind is filtered out.

Radar Data Analysis08.png

  • Run the following command to start the dynamic parameter debugging interface.
 rosrun rqt_reconfigure rqt_reconfigure

Radar Data Analysis09.png

  • Among which:
    • laserAngle : Set the effective angle range to detect the angle in front of the robot.
    • distance : Set the effective distance, data beyond this distance will be filtered.
  • Drag the slider to adjust the parameters, and you can find that the red dot displayed by the radar also changes.

Step 4: Radar obstacle avoidance

  • [Note: Please close the radar-related nodes first, otherwise an error will occur if you start the radar node multiple times.]
  • Enter the following command on the robot side to start the radar obstacle avoidance node.
 roslaunch jetbot_pro laser_avoidance.launch #Start the radar obstacle avoidance node
  • After the program starts, the robot will move forward, and it will automatically turn to avoid obstacles when encountering obstacles.
  • Start the dynamic parameter adjustment interface on the virtual machine side.
  rosrun rqt_reconfigure rqt_reconfigure

Radar Data Analysis10.png

  • Among which:
    • linear: Set the linear speed of the robot moving forward. Note that if the set speed is too fast, it may stop and hit the obstacle in time.
    • angular sets the angular velocity at which the robot turns.
    • Angle sets the detection angle range of the robot. The program detects the left, front, and right directions of the robot. This value sets the detection angle of each direction.
    • Distance sets the obstacle distance. If the distance is less than this value, it will consider an obstacle and turn.
    • start the Robot obstacle avoidance switch, enabled by default, the car will stop after unchecked.

Step 5: Radar Guard

  • [Note: Please close the radar-related nodes first, otherwise an error will occur if you start the radar node multiple times.]
  • Enter the following command on the robot side to start the radar guard node.
roslaunch jetbot_pro laser_warning.launch #Start the radar guard node
  • After the program starts, the robot will detect the closest point in front, and then control the robot to turn to face the closest point.
  • Start the dynamic parameter adjustment interface on the virtual machine, you can check whether the robot is facing the nearest point recorded.
rosrun rviz rviz    

Radar Data Analysis11.png

  • In the TF component, you can uncheck other frames and only check base_footprint to display the robot chassis coordinates.

Radar Data Analysis12.png

  • Start the dynamic parameter adjustment interface on the virtual machine side.
 rosrun rqt_reconfigure rqt_reconfigure

Radar Data Analysis13.png

  • Among which:
    • kp,kd sets the PID parameters, PD adjustment is used in the program, modifying this parameter can optimize the robot following effect.
    • laserAngle sets the detection angle range of the robot, the default detection is 120 degrees in front of the robot.
    • distance sets the detection distance, only detect the distance range less than this value.
    • start: the robot start switch, start by default, and the car will stop after being unchecked.

Step 6: Radar Follow

  • [Note: Please close the radar-related nodes first, otherwise an error will occur if you start the radar node multiple times.]
  • Enter the following command on the robot side to start the radar follower node.
 roslaunch jetbot_pro laser_tracking.launch #Start radar tracking node
  • After the program starts, the robot will detect the closest point in front, and then the robot will follow the closest point.
  • Note: This program needs to be run in an open place, otherwise it will be disturbed by the surrounding environment, and the follow-up effect will not be ideal.
  • Open the RVIZ graphical tool in the virtual machine to view the detection range of the robot.
 rosrun rviz rviz    

Radar Data Analysis14.png

  • Start the dynamic parameter adjustment interface on the virtual machine side.
  rosrun rqt_reconfigure rqt_reconfigure

Radar Data Analysis15.png

  • Among which:
    • linear_kp, linear_kd set the linear speed PID parameters and control the linear speed of the robot.
    • angular_kp, angular_kd set the angular velocity PID parameters and control the angular velocity of the robot.
    • laserAngle sets the detection angle range of the robot, the default detection is 120 degrees in front of the robot.
    • PriorityAngle sets the priority detection angle range of the robot. This value needs to be larger than laserAngle, and the points within this range will be followed first.
    • distance sets the detection distance, only detect the distance range less than this value.
    • start: the robot start switch, start by default, and the car will stop after being unchecked.