Flask Web Controller

../_images/screenshot1.png

Screenshot from the Flask web application used to control the Jetbot

This guide will explain the required steps to install the web controller feature which enables the Jetbot to be controlled from any smartphone or tablet using the touch screen. Two virtual joysticks are used as control inputs and the camera video stream is streamed to the web application background in real-time.

Create WiFi Hotspot from Jetbot

In order to achieve sufficient response when using the Web Controller from your smartphone or tablet, it is recommended to configure the Jetbot to host its own hotspot as a system service. The default hotspot service in Ubuntu currently does not allow to be hosted on the same wlan interface while the Jetbot is already connected to a WiFi network (which is the case for us where the Jetbot is connected to yout laptop WiFi hotspot).

It is therefore needed to install some additional software named linux-wifi-hotspot. The installation procedure and configuration of this software is described below.

  1. Install Linux Hotspot software:

    • sudo apt install -y libgtk-3-dev build-essential cmake gcc g++ pkg-config make hostapd

    • git clone https://github.com/lakinduakash/linux-wifi-hotspot

    • cd linux-wifi-hotspot/src/scripts

    • sudo make install

  2. Clean up after installation (optional):

    • cd ~

    • sudo rm -rd linux-wifi-hotspot

  3. Create system service:

    • Open create_ap.conf by sudo nano /etc/create_ap.conf and change the following entries:

      INTERNET_IFACE=wlan0
      SSID=jetbot<group-number>
      PASSPHRASE=jetbot<group-number>-pwd
      
    • Open/create the service file by executing sudo nano /etc/systemd/system/create_ap.service and paste the following code into the nano editor and save:

      [Unit]
      Description=Create AP Service
      After=network.target
      
      [Service]
      Type=simple
      ExecStart=/usr/bin/create_ap --config /etc/create_ap.conf
      KillSignal=SIGINT
      Restart=on-failure
      RestartSec=5
      
      [Install]
      WantedBy=multi-user.target
      
  4. Enable service to be automatically started after boot/startup:
    • sudo systemctl enable create_ap

  5. Start service
    • sudo systemctl start create_ap

  6. See status of system service
    • sudo systemctl status create_ap

Install Web Application

The Flask Web Application is ready to use and hence is only needed to be added to the ROS launch file and WebController.py file has to be moved from this repo to your own. Follow the steps to install and enable the Web Controller app in your project:

  1. Install Flask:

    • pip install Flask

  2. Copy the two folders ./src/static and ./src/templates to your project in the same folder locations.

  3. Copy the text from ./src/WebController.py onto your Jetbot and make the file executable by executing the following command sudo chmod +x WebController.py

  4. Copy the text from the ROS message file ./msg/WebJoystick.msg onto your Jetbot in the same location.

  5. In order to make ROS being aware of the new ROS message, the message has to be added to the CMakeLists.txt under the section add_message_files(). The new ROS message WebJoystick.msg are added as:

    add_message_files(
        FILES
        ServoSetpoints.msg
        WebJoystick.msg
    )
    
  6. After adding the new ROS message, the catkin_make has to be executed from the from ~/catkin_ws folder. This will build and register the new message.

  7. Add the new node for our Flask Web Controller by adding the line <node name="WebController" pkg="mas507" type="WebController.py" output="screen"/> to the start.launch file.

  8. Connect your smartphone or tablet to the new WiFi hotspot being hosted by the Jetbot.

  9. Start the ROS package using roslaunch mas507 start.launch and visit http://jetbot-desktop<group-number>:8000 on your smartphone or tablet. The video stream from the camera should now be streaming to the webpage background. Try to tap the screen to use the two joysticks on the left and right side of the screen.

Integrate with Main Controller

The two new ROS messages produced by the Flask web application node are now available using the ROS topics \webJoystickLeft and webJoystickRight. Please look at the MainController.py to see how it can be integrated to move the robot. Be aware that the values might be tuned for your specific Jetbot. The implementation and usage of the Web Controller joysticks is also shown below.

#!/usr/bin/env python
"""
Main Control Node
"""
import rospy
import numpy as np
import os
from mas507.msg import ServoSetpoints, WebJoystick
from sensor_msgs.msg import Image
from StrawberryDetector import StrawberryDetector

class Joystick(object):
    def __init__(self):
        self.x = 0
        self.y = 0

    def callback(self, msg):
        self.x = msg.x
        self.y = msg.y

if __name__ == '__main__':
    try:
        # Init ROS node
        rospy.init_node('mainController', anonymous=True)

        # Web Joysticks
        leftJoystick = Joystick()
        rightJoystick = Joystick()

        # Publishers
        pub_servoSetpoints = rospy.Publisher('servoSetpoints', ServoSetpoints, queue_size=1)
        pub_strawberry_detection = rospy.Publisher('strawberry_detection', Image, queue_size=1)
        
        # Strawberry detector
        intrinsicCalibration =  np.load('%s/catkin_ws/src/mas507/data/intrinsicCalibration.npz' % (os.path.expanduser("~")))
        strawberryDetector = StrawberryDetector(pub_strawberry_detection, intrinsicCalibration['mtx'], intrinsicCalibration['dist'])

        # Subscribers
        sub_calibrated = rospy.Subscriber('image_calibrated', Image, strawberryDetector.callback)
        sub_leftJoystick = rospy.Subscriber('webJoystickLeft', WebJoystick, leftJoystick.callback)
        sub_rightJoystick = rospy.Subscriber('webJoystickRight', WebJoystick, rightJoystick.callback)

        # Start Synchronous ROS node execution
        t = 0
        rate = rospy.Rate(10)
        while not rospy.is_shutdown():
            servoSetpoints = ServoSetpoints()

            servoSetpoints.leftWheel  = 315 - rightJoystick.y/2 + leftJoystick.x/7
            servoSetpoints.rightWheel = 305 + rightJoystick.y/2 + leftJoystick.x/7
            pub_servoSetpoints.publish(servoSetpoints)

            t = t + 0.1

            # Sleep remaining time
            rate.sleep()

    except rospy.ROSInterruptException:
        pass