The open source platform provides DIY developers, students and enthusiasts with everything they need to create various AI-based applications. The JetBot kit works on the basis of a small but powerful NVIDIA Jetson Nano computer that provides parallel operation of several sensors and neural networks for object recognition, collision avoidance and other tasks. All the assembly documents and a complete list of complete components for the original NVIDIA JetBot AI robot are available on GitHub (https://github.com/NVIDIA-AI-IOT/jetbot).
It is possible to buy a ready-made set from third-party manufacturers. The kits are presented in various configurations, which allows you to create absolutely unique solutions. I had a set from Waveshare available. The JetBot from Waveshare is equipped with a high-quality chassis, a front-facing camera and all the necessary tools that ensure quick and easy assembly.
Unfortunately, we had to change the platform, the original one turned out to be unstable and weak engines
I installed it on another platform-from the disassembled iRobot Create vacuum cleaner.
Consider installing ROS packages for management and navigation on jetbot.
Robot Operating System (ROS) is a flexible platform (framework) for the development of robot software. This is a set of various tools, libraries and certain rules, the purpose of which is to simplify the tasks of developing robot software.
We use a 64 GB SD card on which the NVIDIA JetPack image is recorded. The NVIDIA JetPack image is based on Ubuntu 18.04 OS. We will install the ROS Melodic version (http://wiki.ros.org/melodic).
# Adding all Ubuntu repositories:
sudo apt-add-repository universe
sudo apt-add-repository multiverse
sudo apt-add-repository restricted
# adding the ROS repository
sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654
# install the ROS Base
sudo apt-get update
sudo apt-get install ros-melodic-ros-base
# adding ROS paths
sudo sh -c ' echo "source /opt/ros/melodic/setup.bash" >> ~ / .bashrc '
We will install the Adafruit libraries to support the TB6612/PCA9685 engine drivers and the SSD1306 debugging OLED display:
# installing pip
sudo apt-get install python-pip
# installing Adafruit libraries
pip install Adafruit-MotorHAT
pip install Adafruit-SSD1306
We will provide the user with access to the i2c bus:
sudo usermod -aG i2c $USER
We will reboot the system so that the changes take effect.
Create a ROS Catkin workspace to store ROS packages:
# creating a workspace catkin mkdir-p ~/workspace/catkin_ws/src
cd ~/workspace/catkin_ws
catkin_make
# add the catkin_ws path to bashrc sudo sh -c ' echo "source ~/workspace/catkin_ws/devel/setup.bash" >> ~/.bashrc'
We close and re-open a new terminal window to make sure that catkin_ws is visible to ROS:
echo $ROS_PACKAGE_PATH
We clone and build the jetson-inference package. The package uses NVIDIA TensorRT for efficient deployment of neural networks on the built-in Jetson platform.
# installing git and cmake
sudo apt-get install git cmake
# cloning the repository and cd submodules ~ / workspace
git clone https://github.com/dusty-nv/jetson-inference
cd jetson-inference
git submodule update --init
# build from the source code
mkdir build
cd build
cmake ../
make
# install libraries
sudo make install
Cloning and building the ROS package ros_deep_learning
# install dependencies
sudo apt-get install ros-melodic-vision-msgs ros-melodic-image-transport ros-melodic-image-publisher
# cloning the cd repository ~/workspace/catkin_ws/src
git clone https://github.com/dusty-nv/ros_deep_learning
# build catkin
cd ~/workspace/catkin_ws
catkin_make
# checking that ROS finds the package that the package is ros_deep_learning
rospack find ros_deep_learning
Cloning and building the jetbot_ros ROS package
# cloning the repository
cd ~/workspace/catkin_ws/src
git clone https://github.com/dusty-nv/jetbot_ros
# building the package
cd ~/workspace/catkin_ws
catkin_make
# checking that the ROS finds the package that the jetbot_ros package
$ rospack find jetbot_ros
Testing ros_jetbot
Open the terminal and launch
roscore
In the second terminal, we launch the jetbot_motors node
rosrun jetbot_ros jetbot_motors.py
And then the problem is Import error: No module named Adafruit_MotorHAT, although the library has already been installed (see above).
But the library was installed in python3, and ROS uses python2. 7
Install the Adafruit_MotorHAT library for python2. 7
python2. 7-m pip install Adafruit_MotorHAT
Now the launch is normal and in the next terminal we check that the corresponding nodes and topics are running in ROS
Here is a list of topics
- /jetbot_motors/cmd_dir - relative heading (degree [-180.0, 180.0], speed [-1.0, 1.0])
- /jetbot_motors/cmd_raw - raw L/R motor commands (speed [-1.0, 1.0], speed [-1.0, 1.0])
- /jetbot_motors/cmd_str - simple string commands (left/right/forward/backward/stop)
But, unfortunately, in jetbot_motors.py the processing of messages received from the topic /jetbot_motors/cmd_str is registered
We try to send them from the terminal (these are movements forward, backward, left, right and stop)
rostopic pub /jetbot_motors/cmd_str std_msgs/String --once "forward"
rostopic pub /jetbot_motors/cmd_str std_msgs/String --once "backward"
rostopic pub /jetbot_motors/cmd_str std_msgs/String --once "left"
rostopic pub /jetbot_motors/cmd_str std_msgs/String --once "right"
rostopic pub /jetbot_motors/cmd_str std_msgs/String --once "stop"
Again the problem !!! No sign of movement. You need to make changes to the file jetbot_motors.py, change the set_speed() and all_stop () functions.
I have created a new file jetbot_motors_1.py and made the following changes changes
# sets motor speed between [-1.0, 1.0]
def set_speed(motor_ID, value):
max_pwm = 200.0
speed = int(min(max(abs(value * max_pwm), 0), max_pwm))
a = b = 0
if motor_ID == 1:
motor = motor_left
a=1
b=0
elif motor_ID == 2:
motor = motor_right
a=2
b=3
else:
rospy.logerror('set_speed(%d, %f) -> invalid motor_ID=%d', motor_ID, value, motor_ID)
return
motor.setSpeed(speed)
if value < 0:
motor.run(Adafruit_MotorHAT.FORWARD)
motor.MC._pwm.setPWM(a,0,0)
motor.MC._pwm.setPWM(b,0,speed*16)
elif value > 0:
motor.run(Adafruit_MotorHAT.BACKWARD)
motor.MC._pwm.setPWM(a,0,speed*16)
motor.MC._pwm.setPWM(b,0,0)
else:
motor.run(Adafruit_MotorHAT.RELEASE)
motor.MC._pwm.setPWM(a,0,0)
motor.MC._pwm.setPWM(b,0,0)
# stops all motors
def all_stop():
set_speed(motor_left_ID, 0.0)
set_speed(motor_right_ID, 0.0)
Now jetbot responds to sending messages, can move forward, backward, left, right and stop. But this is all with one speed, regulated by this value
max_pwm = 200.0
It is necessary to register the implementation of movement at different speeds. For now, we will do the simplest, we will use sending std_msgs/String messages to the topic /jetbot_motors/cmd_raw
# raw L/R motor commands (speed, speed)
def on_cmd_raw(msg):
rospy.loginfo(rospy.get_caller_id() + ' cmd_raw=%s', msg.data)
speeds=msg. data. split(',')
set_speed(motor_left_ID, float( speeds[0]))
set_speed(motor_right_ID, float (speeds[1]))
And check, I send similar commands
rostopic pub /jetbot_motors/cmd_raw std_msgs/String --once " 0.9,-0.7"
Now let's consider sending information messages to the OLED display.
First, install the library
python2.7 -m pip install Adafruit_SSD1306
We launch the jetbot_oled node to display system information and user text:
rosrun jetbot_ros jetbot_oled.py
By default, the jetbot_oled screen is updated every second with the latest data on the use of memory, disk space and IP addresses.
The node will also listen to the topic /jetbot_oled/user_text to receive string messages from the user and display them on the screen
rostopic pub /jetbot_oled/ user_text std_msgs/String --once "HELLO!"
Using the camera
To start streaming from the JetBot camera, launch the jetbot_camera node
rosrun jetbot_ros jetbot_camera
Video frames will be published in the topic /jetbot_camera/raw in the form of sensor_msgs messages::Image in BGR8 encoding.
Install the image_view package, and then subscribe to it /jetbot_camera/raw from the new terminal:
sudo apt-get install ros-melodic-image-view
rosrun image_view image_view image:=/jetbot_camera/raw
After that, a window should open in which the video from the camera will be displayed in real time.
And also sending messages from the subject /jetbot_motors/cmd_raw must be changed. Namely, the type of messages on geometry_msgs/Twist, which is widely used in ROS.
I have created a new file jetbot_motors_2.py and made the following changes changes
#!/usr/bin/env python
import rospy
import time
import math
from Adafruit_MotorHAT import Adafruit_MotorHAT
from std_msgs.msg import String
from geometry_msgs.msg import Twist
PWM_MIN=0.5
PWM_MAX=1.0
# sets motor speed between [-1.0, 1.0]
def set_speed(motor_ID, value):
max_pwm = 200.0
speed = int(min(max(abs(value * max_pwm), 0), max_pwm))
a = b = 0
if motor_ID == 1:
motor = motor_left
a=1
b=0
elif motor_ID == 2:
motor = motor_right
a=2
b=3
else:
rospy.logerror('set_speed(%d, %f) -> invalid motor_ID=%d', motor_ID, value, motor_ID)
return
def motor.setSpeed(speed)
if value < 0:
motor.run(Adafruit_MotorHAT.FORWARD)
motor.MC._pwm.setPWM(a,0,0)
motor.MC._pwm.setPWM(b,0,speed*16)
elif value > 0:
motor.run(Adafruit_MotorHAT.BACKWARD)
motor.MC._pwm.setPWM(a,0,speed*16)
motor.MC._pwm.setPWM(b,0,0)
else:
motor.run(Adafruit_MotorHAT.RELEASE)
motor.MC._pwm.setPWM(a,0,0)
motor.MC._pwm.setPWM(b,0,0)
# stops all motors
def all_stop():
set_speed(motor_left_ID, 0.0)
set_speed(motor_right_ID, 0.0)
# directional commands (degree, speed)
def on_cmd_dir(msg):
rospy.loginfo(rospy.get_caller_id() + ' cmd_dir=%s', msg.data)
# raw L/R motor commands (speed, speed)
def on_cmd_raw(msg):
rospy.loginfo("msg cmd_raw")
rospy.loginfo(msg)
x=max(min(msg.linear.x,1.0),-1.0)
z=max(min(msg.angular.z,1.0),-1.0)
l=(x-z)/2
r=(x+z)/2
#rospy.loginfo(x)
#rospy.loginfo(z)
#rospy.loginfo(l)
#rospy.loginfo(r)
lpwm= PWM_MIN+math.fabs(l)*(PWM_MAX-PWM_MIN)
rpwm= PWM_MIN+math.fabs(r)*(PWM_MAX-PWM_MIN)
#rospy.loginfo(lpwm)
#rospy.loginfo(rpwm)
kl=1 if l>0 else -1
kr=1 if r>0 else -1
if l==0 : kl=0
if r==0 : kr=0
set_speed(motor_left_ID, kl*lpwm )
set_speed(motor_right_ID, kr*rpwm)
# simple string commands (left/right/forward/backward/stop)
def on_cmd_str(msg):
rospy.loginfo(rospy.get_caller_id() + ' cmd_str=%s', msg.data)
if msg.data.lower() == "left":
set_speed(motor_left_ID, -1.0)
set_speed(motor_right_ID, 1.0)
elif msg.data.lower() == "right":
set_speed(motor_left_ID, 1.0)
set_speed(motor_right_ID, -1.0)
elif msg.data.lower() == "forward":
set_speed(motor_left_ID, 1.0)
set_speed(motor_right_ID, 1.0)
elif msg.data.lower() == "backward":
set_speed(motor_left_ID, -1.0)
set_speed(motor_right_ID, -1.0)
elif msg.data.lower() == "stop":
all_stop()
else:
rospy.logerror(rospy.get_caller_id() + ' invalid cmd_str=%s', msg.data)
# initialization
if __name__ == '__main__':
# setup motor controller
motor_driver = Adafruit_MotorHAT(i2c_bus=1)
motor_left_ID = 1
motor_right_ID = 2
motor_left = motor_driver.getMotor(motor_left_ID)
motor_right = motor_driver.getMotor(motor_right_ID)
# stop the motors as precaution
all_stop()
# setup ros node
rospy.init_node('jetbot_motors')
rospy.Subscriber('~cmd_dir', String, on_cmd_dir)
rospy.Subscriber('~cmd_raw', Twist, on_cmd_raw)
rospy.Subscriber('~cmd_str', String, on_cmd_str)
# start running
rospy.spin()
# stop motors before exiting
all_stop() And
of course, the launch of all nodes by launching the launch command file. We place the launch01.launch file with catkin_ws/src/jetbot_ros/launch
<launch>
<node name="jetbot_motors" pkg="jetbot_ros" type="jetbot_motors_2.py">
</node>
<node name="jetbot_camera" pkg="jetbot_ros" type="jetbot_camera">
</node>
<node name="jetbot_oled" pkg="jetbot_ros" type="jetbot_oled.py">
</node>
</launch>
Running a batch file
roslaunch jetbot_ros launch01.launch
Let's control the robot from a remote computer. We will use the rosbridge package. Rosbridge allows external clients (in our case, the browser) to have access to ROS topics and services (publishing and receiving from topics, calling services). Rosbridge is part of the rosbridge_suite meta-package, which includes various additional packages for implementing the rosbridge protocol.
The rosbridge_suite package is a set of packages that implement the rosbridge protocol and provide the WebSocket transport layer.
The packages include:
rosbridge_library - the basic rosbridge package. Rosbridge_library is responsible for receiving the JSON string and sending commands to ROS and vice versa.
rosapi-makes certain ROS actions available through service calls that are usually reserved for ROS client libraries. This includes getting and setting parameters, getting a list of topics, and much more.
rosbridge_server-provides a connection via WebSocket so that browsers can "talk to rosbridge". Roslibjs is a JavaScript library for the browser that can interact with ROS via rosbridge_server.
Installing the package
sudo apt-get install ros-melodic-rosbridge-suite
Create a command file launch02.launch in the project folder jetbot_ros in the launch folder
<launch>
<include file="$(find rosbridge_server)/launch/rosbridge_websocket.launch"/>
<node name="jetbot_motors" pkg="jetbot_ros" type="jetbot_motors_2.py">
</node>
<node name="jetbot_oled" pkg="jetbot_ros" type="jetbot_oled.py">
</node>
</launch>
And running the command file
1 terminal
roscore
2 terminal
roslaunch jetbot_ros launch02.launch
To organize the web interface, you need to install a web server.
sudo apt-get install apache2
Now our html page will be located in the /var/www/html folder. The Library roslib.min.js we will put it in the js folder.
Create an html file index01.html where we will connect to ROS via websocket 9090 and send messages from the form to the ROS /pub_txt_msg topic and receive and display messages coming to the ROS /sub_txt_msg topic on the page
<!DOCTYPE html>
<html>
<head>
<meta charset="utf-8" />
<script type="text/javascript" src="js/roslib.min.js"></script>
<script type="text/javascript" type="text/javascript">
var ros = new ROSLIB.Ros({
url : 'ws://192.168.0.111:9090'
});
ros.on('connection', function() {
document.getElementById("status").innerHTML = "Connected";
});
ros.on('error', function(error) {
document.getElementById("status").innerHTML = "Error";
});
ros.on('close', function() {
document.getElementById("status").innerHTML = "Closed";
});
var txt_listener = new ROSLIB.Topic({
ros : ros,
name : '/sub_txt_msg',
messageType : 'std_msgs/String'
});
txt_listener.subscribe(function(m) {
document.getElementById("msg").innerHTML = m.data;
});
var pub1=new ROSLIB.Topic ({
ros: ros,
name : '/pub_txt_msg',
messageType : 'std_msgs/String'
});
function send_ros() {
var msg=new ROSLIB.Message ({"data" : document.getElementById("putdata").value});
pub1.publish(msg);
}
</script>
</head>
<body>
<h1>Simple ROS User Interface</h1>
<p>Connection status: <span id="status"></span></p>
<p>Last /txt_msg received: <span id="msg"></span></p>
<p><form id=formoptions name=formoptions action="javascript:void();" onsubmit="feturn false;">
send to /pub_txt_msg <br>
<input name=putdata id=putdata>
<button id='button1' value='send' onclick='send_ros();'>Send</button>
</form>
</p>
</body>
</html>
Launching the page in the browser index01.html
Messages in the subject /sub_txt_msg
rostopic pub /sub_txt_msg std_msgs/String "Hello? browser"
Viewing messages sent from the browser to the subject /pub_txt_msg
rostopic echo /pub_txt_msg
In the future, we will run all the nodes from command files
Output of a streaming image from the camera to a web page
To output a streaming image from the camera to a web page, install the web_video_server ros package
sudo apt-get install ros-melodic-web-video-server
Creating a command file launch03. launch
<launch>
<include file="$(find rosbridge_server)/launch/rosbridge_websocket.launch"/>
<node name="jetbot_motors" pkg="jetbot_ros" type="jetbot_motors_2.py">
</node>
<node name="jetbot_oled" pkg="jetbot_ros" type="jetbot_oled.py">
</node>
<node name="jetbot_camera" pkg="jetbot_ros" type="jetbot_camera">
</node>
<node name="web_video_server" pkg="web_video_server" type="web_video_server">
<param name="port" value="8090"></param>
<param name="address" value="192.168.0.111"></param>
</node>
</launch>
Viewing a video on a page
Creating a file index02.html to control the robot's movement and view the image from the camera. We use the nipplejs library.js
<!DOCTYPE html>
<html>
<head>
<meta charset="utf-8" />
<script type="text/javascript" src="js/roslib.min.js"></script>
<script type="text/javascript" src="js/nipplejs.js"></script>
<script type="text/javascript" type="text/javascript">
var ros = new ROSLIB.Ros({
url : 'ws://192.168.0.111:9090'
});
ros.on('connection', function() {
document.getElementById("status").innerHTML = "Connected";
});
ros.on('error', function(error) {
document.getElementById("status").innerHTML = "Error";
});
ros.on('close', function() {
document.getElementById("status").innerHTML = "Closed";
});
var txt_listener = new ROSLIB.Topic({
ros : ros,
name : '/txt_msg',
messageType : 'std_msgs/String'
});
txt_listener.subscribe(function(m) {
document.getElementById("msg").innerHTML = m.data;
});
cmd_vel_listener = new ROSLIB.Topic({
ros : ros,
name : "/cmd_vel",
messageType : 'geometry_msgs/Twist'
});
move = function (linear, angular) {
var twist = new ROSLIB.Message({
linear: {
x: linear,
y: 0,
z: 0
},
angular: {
x: 0,
y: 0,
z: angular
}
});
cmd_vel_listener.publish(twist);
}
createJoystick = function () {
var options = {
zone: document.getElementById('zone_joystick'),
threshold: 0.1,
position: { left: 50 + '%' },
mode: 'static',
size: 150,
color: '#000000',
};
manager = nipplejs.create(options);
linear_speed = 0;
angular_speed = 0;
manager.on('start', function (event, nipple) {
timer = setInterval(function () {
move(linear_speed, angular_speed);
}, 25);
});
manager.on('move', function (event, nipple) {
max_linear = 1.0; // m/s
max_angular = 1.0; // rad/s
max_distance = 75.0; // pixels;
linear_speed = Math.sin(nipple.angle.radian) * max_linear * nipple.distance/max_distance;
angular_speed = -Math.cos(nipple.angle.radian) * max_angular * nipple.distance/max_distance;
});
manager.on('end', function () {
if (timer) {
clearInterval(timer);
}
self.move(0, 0);
});
}
window.onload = function () {
createJoystick();
}
</script>
</head>
<body>
<h1>Simple ROS User Interface</h1>
<p>Connection status: <span id="status"></span></p>
<p>Last /txt_msg received: <span id="msg"></span></p>
<div id="zone_joystick" style="position: relative;"></div>
</body>
</html>
After launching the page, we can control the robot's movement. Page view
Если необходимо добавить управление с джойстика, то создадим скрипт subscriber, ловящий данные, публикуемые пакетом joy и преобразующий их в данные для ноды /jetbot_motors/cmd_raw.
Содержимое скрипта jetbot_joy.py
#!/usr/bin/env python
import rospy
import time
import math
from sensor_msgs.msg import Joy
from std_msgs.msg import String
from geometry_msgs.msg import Twist
pub=rospy.Publisher("/jetbot_motors/cmd_raw",Twist)
def controller(data):
rospy.loginfo(str(data.axes[0])+" "+str(data.axes[1]))
msg=Twist()
msg.linear.x=data.axes[0];
msg.linear.y=0.0;
msg.linear.z=0.0;
msg.angular.x=0.0;
msg.angular.y=0.0;
msg.angular.z=data.axes[1];
pub.publish(msg)
def listener():
rospy.init_node('jetbot_joy')
rospy.sleep(1.0)
sub = rospy.Subscriber("joy",Joy,controller)
rospy.spin()
if __name__ == '__main__':
listener()
И командный файл launch04.launch
<launch>
<include file="$(find rosbridge_server)/launch/rosbridge_websocket.launch"/>
<node name="jetbot_motors" pkg="jetbot_ros" type="jetbot_motors_2.py">
</node>
<node name="jetbot_oled" pkg="jetbot_ros" type="jetbot_oled.py">
</node>
<node name="jetbot_camera" pkg="jetbot_ros" type="jetbot_camera">
</node>
<node name="joy_node" pkg="joy" type="joy_node">
</node>
<node name="jetbot_joy" pkg="jetbot_ros" type="jetbot_joy.py">
</node>
<node name="web_video_server" pkg="web_video_server" type="web_video_server">
<param name="port" value="8090"></param>
<param name="address" value="192.168.0.36"></param>
</node>
</launch>
And video
Comments