Jupyter Notebook [Melodic]

Installation

Run the below code in terminal to install

$ sudo apt install python-pip

Remember the robot's password is the single digit number "1".

After installing, upgrade pip by running the below command in the terminal shell.

$ pip install --upgrade pip

Next, we install jupyter, matplotib, pandas, and numpy by running the below command in the terminal shell. This may take a while.

$ pip install jupyter matplotlib numpy pandas

Open Jupyter Notebook

In the command line, run the below line to open Jupyter Notebook. Jupyter Notebook is a __ that will run on your browser.

$ jupyter notebook

Running the command, you should see output like above, before being redirected to a webpage like the image below.

Next, navigate to the Documents folder and press the "New" button like below. Then press "Python 2" to create a new Python 2 script.

Control R1mini with Jupyter Notebook

Moving Robot

Import necessary libaries -- rospy to control all ROS-based functions in Python, and Twist and Point datatypes of geometry_msgs.msg

import rospy
from geometry_msgs.msg import Point, Twist

Initialize necessary variables. Instantiating speed as a variable of the Twist datatype, initializing a rosnode called "test_cmd_vel", setting the rate (how frequently to run the program) to 100, and initialize a publisher to the /cmd_vel topic of Twist datatype called pub.

speed = Twist()
rospy.init_node("test_cmd_vel")
rate = rospy.Rate(100)
pub = rospy.Publisher("/cmd_vel", Twist, queue_size=1)

Next, set speed in the x-direction to 0.5

speed.linear.x = 0.5

Next, type the below three lines to move the robot.

while True:
    pub.publish(speed)
    rate.sleep()

Press the square to stop the robot.

Checking Battery State

To check the battery state of the R1mini, run the below code.

from omo_r1mini_bringup.srv import Battery

bat_status = rospy.ServiceProxy("/battery_status", Battery)
bat_status()

The output should look like the image above.

Changing LED Colors

To change the colors of the LED at the front of the robot, enter the below code into the a code block. The below code sets the LEDs to an RGB value of 250, 50, 50. You can change what color you would like by adjusting the RGB values in line 4.

from omo_r1mini_bringup.srv import Color

set_led = rospy.ServiceProxy("/set_led_color", Color)
set_led(250, 50, 50)

Video Demonstration

To see a a video demonstration for this page, check out this link: https://www.youtube.com/watch?v=LY0JIf_0XQ4

Last updated