Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

01

Introduction

In the previous two articles: “Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 1)” we introduced the hardware needed for a Jetson Nano car; in “Open Source! A Step-by-Step Guide to Driving Arduino + ROS Car Motors” we discussed how to use Arduino and its expansion board to achieve differential control and PID speed regulation of two DC geared motors.

Today, we will explain how to configure ros_arduino_bridge in Jetson Nano, how to configure and use the IMU, and how to use the CSI camera.

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

(Acrylic-TT motor version chassis)

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

(Complete acrylic-37 motor version)

This time, we mainly use our designed black acrylic version as an example to teach you how to configure the software part. Let me elaborate on the specific steps.

02

Real Machine Platform

  • Jetson Nano + Arduino Mega 2560 driven two-wheel differential car

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

(ps: with four turn signals, the program has been merged and updated)

  • Raspberry Pi Camera (V2 version)

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

  • Rotatable camera bracket (3D printed)

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

  • Test track

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

  • 9-axis IMU

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

02

Debugging the ros_arduino_bridge program

This program runs on the Ubuntu + ROS Melodic system, which means that the system running on Jetson Nano needs to install the corresponding runtime environment. We will not describe how to flash the system and install ROS on Jetson Nano here, as Nvidia’s corresponding website has detailed tutorials. Here, we mainly record how to configure the ros_arduino_bridge ROS package.

  • ros_arduino_bridge file structure

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

(ps: win10 cmd command is tree /F)

The left side of the above diagram is interpreted as follows:

ros_arduino_bridge: stores the compilation files and dependency records of this functional package.txt and xmlros_arduino_firmware: this is an Arduino template framework provided by the author when open-sourcingros_arduino_msgs: stores custom message msg and service srv filesros_arduino_python: stores the Python ROS node program that interacts with Arduino through serial data

The above red numbers are interpreted as follows:

  • 1 my_arduino_params.yaml

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

According to the introduction in the above image, modify each parameter in the configuration file to adapt to your vehicle, while (timeout, rate, sensorstate_rate, base_controller_rate) can remain unchanged.

  • 2 arduino_driver.py

This .py file contains some functions for serial port operations written by the original author:

Open/Close the serial port:

def open(self):    ''' Open the serial port.    '''    self.port.open()    def close(self):    ''' Close the serial port.    '''    self.port.close()

Serial port receive/send functions:

def send(self, cmd):        ''' This command should not be used on its own: it is called by the execute commands            below in a thread safe manner.        '''        self.port.write(cmd + '\r')def recv(self, timeout=0.5):    timeout = min(timeout, self.timeout)    ''' This command should not be used on its own: it is called by the execute commands        below in a thread safe manner.  Note: we use read() instead of readline() since        readline() tends to return garbage characters from the Arduino    '''    c = ''    value = ''    attempts = 0    # Check if sending is complete    while c != '\r':        c = self.port.read(1)        value += c        attempts += 1        if attempts * self.interCharTimeout > timeout:           return None     value = value.strip('\r')     return value

This file also contains many functions based on serial port operations. To simplify the initial learning and familiarization cost, we made slight modifications to the Arduino code, keeping only the main functions required for the ROS car. However, to facilitate further learning and customization, we retained the function operations in arduino_driver.py.

  • 3 arduino_sensors.py

Subsequent supplements

  • 4 base_controller.py

This file mainly subscribes to the speed topic data “cmd_vel” published by other nodes, and then decomposes the speed into the number of pulses required for motor speed control based on the parameters of the physical car; at the same time, it also estimates the trajectory information data “wheel_odom” based on the actual feedback of the motor encoder. The explanations are as follows:

Speed (cmd_vel) –> Target encoder values required by the motor:

# Callback function for cmd_vel topic# self.encoder_resolution encoder resolution# self.gear_reduction motor reduction ratio# self.wheel_diameter wheel diameter# ticks_per_meter = self.encoder_resolution * self.gear_reduction  / (self.wheel_diameter * pi)( pulses / meter )def cmdVelCallback(self, req):    self.last_cmd_vel = rospy.Time.now()    x = req.linear.x         # m/s    th = req.angular.z       # rad/s    if x == 0:        # Rotate in place        right = th * self.wheel_track / 2.0            left = -right    elif th == 0:        # Move forward/backward        left = right = x    else:        # Move with a certain linear and angular speed        left = x - th * self.wheel_track / 2.0      # self.wheel_track wheel track          right = x + th * self.wheel_track / 2.0     # self.arduino.PID_RATE  PID execution frequency         self.v_des_left = int(left * self.ticks_per_meter / self.arduino.PID_RATE)             self.v_des_right = int(right * self.ticks_per_meter / self.arduino.PID_RATE)         

The actual encoder values of the motor –> Trajectory information (wheel_odom):

def poll(self):    now = rospy.Time.now()    if now > self.t_next:        try:            left_enc, right_enc = self.arduino.get_encoder_counts()        except:            self.bad_encoder_count += 1            rospy.logerr("Encoder exception count: " + str(self.bad_encoder_count))            return           dt = now - self.then        self.then = now        dt = dt.to_sec()  # Convert time unit to seconds.        # According to the number of pulses received within the adjacent sampling time, calculate how much each tire has advanced in meters.        if self.enc_left == None:            dright = 0            dleft = 0        else:            dright = (right_enc - self.enc_right) / self.ticks_per_meter            dleft = (left_enc - self.enc_left) / self.ticks_per_meter        self.enc_right = right_enc        self.enc_left = left_enc        # Solve the combined displacement through the difference in travel of each wheel of the differential car, and then calculate the combined speed.        dxy_ave = (dright + dleft) / 2.0        dth = (dright - dleft) / self.wheel_track        vxy = dxy_ave / dt        vth = dth / dt        # Calculate the travel of the car in the world coordinate system based on the combined displacement and speed.            if (dxy_ave != 0):            dx = cos(dth) * dxy_ave   #+            dy = sin(dth) * dxy_ave  #-             self.x += (cos(self.th) * dx - sin(self.th) * dy)            self.y += (sin(self.th) * dx + cos(self.th) * dy)            if (dth != 0):            self.th += dth         # Solve the pose data of the odom topic        quaternion = Quaternion()        quaternion.x = 0.0         quaternion.y = 0.0        quaternion.z = sin(self.th / 2.0)        quaternion.w = cos(self.th / 2.0)            # Assign and prepare to publish odometry topic data.        odom = Odometry()        odom.header.frame_id = "wheel_odom"        odom.child_frame_id = self.base_frame        odom.header.stamp = now        odom.pose.pose.position.x = self.x        odom.pose.pose.position.y = self.y        odom.pose.pose.position.z = 0        odom.pose.pose.orientation = quaternion        odom.twist.twist.linear.x = vxy        odom.twist.twist.linear.y = 0        odom.twist.twist.angular.z = vth        # Set covariance data to distinguish when fusing with IMU.        if vxy == 0 and vth == 0 :            odom.pose.covariance = ODOM_POSE_COVARIANCE2            odom.twist.covariance = ODOM_TWIST_COVARIANCE2        else :            odom.pose.covariance = ODOM_POSE_COVARIANCE            odom.twist.covariance = ODOM_TWIST_COVARIANCE        self.odomPub.publish(odom)

The above code has been uploaded to our open-source repository, welcome to download and experience:

https://github.com/COONEO/Arduino_Jetson_nano_ROS_Car.git

03

Debugging the IMU program

  • Purpose of using IMU

The main reason is that when using wheel odometry alone for gmapping, there is a phenomenon of map drift when turning. A common method is to use IMU data to fuse with wheel odometry, inputting the fused odometry data into the gmapping method to achieve mapping functionality.

The IMU module we selected is a 9-axis with temperature compensation, which, compared to 6-axis, has a magnetometer. This sensor can effectively correct the zero drift of the Z-axis rotation direction, making the fused odometry data better. By looking at the definition of IMU data in ROS, we have:

Header header
geometry_msgs/Quaternion orientationfloat64[9] orientation_covariance # Row major about x, y, z axes
geometry_msgs/Vector3 angular_velocityfloat64[9] angular_velocity_covariance # Row major about x, y, z axes
geometry_msgs/Vector3 linear_accelerationfloat64[9] linear_acceleration_covariance # Row major x, y, z
  • Configuring the IMU

Combining the above definitions and the current practical usage needs, we wrote a ROS package that converts the data output from the IMU module into ROS IMU topic data after reading the IMU communication protocol. Before running this package, it is necessary to configure the IMU module using the manufacturer’s provided Windows 10 host software. The specific configuration steps are as follows:

Refer to the user manual in the “imu_901/resource_folder” folder and use the Windows 10 host software: “MiniIMU.exe” to configure the module as follows:

1. Change the baud rate to: 115200

2. Modify the output items in the configuration to: acceleration, angular velocity, angle, magnetic field, quaternion.

3. Change the output frequency in the configuration to: 200Hz

4. Following the video tutorial on the official website, use the “MiniIMU.exe” software to calibrate the module (acceleration, angle, magnetic field). The tutorial video is as follows:

http://wiki.wit-motion.com/doku.php?id=jy901%E8%B5%84%E6%96%99
  • Using the IMU under ROS

The program has been placed in our repository, download it from the following link:

https://github.com/COONEO/Arduino_Jetson_nano_ROS_Car.git

Place the catkin_ws folder in your Home directory

cd catkin_wsrosdep install --from-paths src --ignore-src -ycatkin_make -jsource devel/setup.bash

Use a USB-Type C data cable to connect the computer and IMU, check the virtual port number assigned in the /dev directory (generally: ttyUSB*). If only one device is plugged in, it must be: ttyUSB0. As shown in the screenshot in the lower right corner of my computer:

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

If you are using our Jetson Nano environment, it has already been remapped through the IMU ID, and the new name is IMU_PORT, and the imu_901.launch file is also opened on that port. If your host does not have it, it is recommended to check our article “Building ROS Robots – Ubuntu Binding Serial Devices” to bind the serial port and remap it.

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

The imu_901.launch file runs the imu_complementary_filter_node, tf, imu_901_node, and other nodes. Two tf describe the positional relationship between the IMU topic data and the coordinate system base_link (three-axis translation + three-axis rotation). A friendly reminder: here the origin of the base_link coordinate system is specified to be in the middle of the driving wheels of the two-wheel differential car, with X facing forward, Y facing left, and Z facing up. Additionally, since the car generally carries a screen, we have commented out the Rviz visualization node by default. The running process is as follows:

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

Additionally, by using: rostopic list you can find the IMU_901 published topic data:

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

Among them:

imu is pose information:

mag is magnetometer information;

Both are published at a frequency of 200Hz.

  • The above code has been uploaded to our open-source repository, welcome to download and experience:

https://github.com/COONEO/Arduino_Jetson_nano_ROS_Car.git

04

Debugging the Raspberry Pi CSI Camera V2 version

Since the Jetson Nano cannot directly obtain the video stream from the CSI camera via the usb_cam ROS package, after searching online, we found that a great developer has open-sourced a program called gscam ROS package, the link is as follows:

http://wiki.ros.org/gscam

We have adapted the ROS startup file for the camera; simply plug in the Raspberry Pi V2 camera with the CSI connector, and by running the corresponding launch file, you can obtain the video stream from that camera. The specific process is as follows:

cd catkin_ws# If not compiled, then catkin_makesource devel/setup.bashroslaunch jetson_nano_csi_cam_ros jetson_csi_cam.launch 

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

(ps: here I ssh into the Jetson Nano host, friends without a screen can try this)

At this point, in the local terminal, you can see the following output by using rostopic list:

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

Additionally, you can view the image using rqt_image_view.

rosrun rqt_image_view rqt_image_view

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

(It’s snowing heavily at home, it’s very quiet in the mountains)

05

Outlook and Easter Eggs

Outlook:

In the upcoming articles, we will continue to update: Mapping Section, Navigation Section, Camera ApplicationsSection. In fact, the differences between the Jetson Nano version and the Raspberry Pi version are not significant. If you want to achieve the above functions faster, you can also refer to our Raspberry Pi ROS car articles and code repositories.
https://github.com/COONEO/Arduino_Raspberry_ROS_Car.git   # Temporarily finishedhttps://github.com/COONEO/Arduino_Jetson_nano_ROS_Car.git    # Being continuously updated
Easter Egg:
Welcome to join our community, aimed at friends who love robot development, to facilitate everyone to learn, share, and communicate about intelligent robot creation, and to meet more like-minded friends. There are also periodic community exclusive benefits! Follow our public account to get the group joining method. Let robot/unmanned driving development be more efficient!

Creating is not easy. If you like this content, please share it with your friends, share and exchange the joy of creation, and inspire us to create more robot development strategies for everyone. Let’s learn by doing together!

———

Recommended Reading:
The robot tapped you, how about simulation testing?
Robot target detection | Recognizing you only takes a moment
The flat world in the robot’s brain
Understanding PID algorithm in three minutes
Gesture recognition and control | “Contactless” mode during the epidemic
ROS takes you through simulation and reality
Depth camera | The intelligent eye of the robotic arm
Odometry | The distance between you and autonomous mobile robots
Mystery unboxing | NEOR mini user feedback

Building a ROS open-source mini unmanned vehicle from scratch

Standing on the shoulders of PX4-Autopilot: Outdoor unmanned driving path planning

NEOR mini runs wildly on the track

Building an open-source crop inspection robot from scratch

Open Source! A Step-by-Step Guide to Building an Arduino + Raspberry Pi ROS Car (Part 1)

Open Source! A Step-by-Step Guide to Building an Arduino + Raspberry Pi ROS Car (Part 2)

Building ROS Robots – Ubuntu Binding Serial Devices

Open Source! Vision Line Following ROS Car Based on OpenCV

Open Source! Webots + ABB Robot Arm Inverse Kinematics Calculation Building ROS Robots – Raspberry Pi System Image Copying and Mounting Free Memory
Step-by-Step Guide to Velodyne Lidar Simulation + 3D Mapping
Open Source! Step-by-Step Guide to Multi-channel Ultrasonic Sensor Obstacle Avoidance Simulation
Camera Calibration and Distortion Correction – Taking Raspberry Pi Wide Angle as an Example
Raspberry Pi Wide Angle Camera Target Detection and Monocular Distance Measurement
Building ROS Robots – Ackermann Chassis Odometry Calculation Node
Building ROS Robots – Publishing Navigation Target Points with Programs
Building ROS Robots – Step-by-Step Guide to Implementing 2D Mapping with Gmapping
Building ROS Robots – Overview of LiDAR 2D Mapping Methods
Actual Measurement! ROS Robot 400 Square Meter Circular Floor Mapping Method Analysis
Open Source! Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 1)
Open Source! Step-by-Step Guide to Driving Arduino + ROS Car Motors
2021 Free Open Resource Sharing – Ackermann and Differential Chassis Series Simulation
2021 Free Open Resource Sharing – Building ROS Car Series from ScratchNEOR mini self-collected data set LeGO-LOAM mapping

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

Open Source! A Step-by-Step Guide to Building an Arduino + NVIDIA Jetson ROS Car (Part 2)

Leave a Comment

Your email address will not be published. Required fields are marked *