Navigation [Melodic]

Navigation using R1mini on ROS1 Melodic.

Running autonomous navigtion

To begin autonomous navigation, enter the below line to the command line.

$ roslaunch omo_r1mini_navigation omo_r1mini_navigation.launch

Running the above command, you should get terminal output similar to the image below.

Just like SLAM, to see the rviz visualization in action, run the below line in the terminal shell.

$ roslaunch omo_r1mini_navigation omo_r1mini_navigation_rviz.launch

Running the above code, an rviz GUI should appear and show an image similar to the above.

Autonomous navigation using GUI

At the top left of the rviz GUI, press "2D Pose Estimate". This will allow you to select the approximate position of the robot with respect to the map.

Once the robot is roughly aligned to the map, press "2D Nav Goal" and then choose lect the location and orientation of the desired endpoint on the map. The robot will perform autonomous navigation and path planning from the current pose to the desired end pose. The process should look like the images below.

Autonomous navigation using code

Alternatively, we can use Python code to tell our robot which pose to end at. Jupyter Notebook will be used for the demo.

First, turn on Jupyter Notebook by running the below command in terminal.

$ jupyter notebook

First, enter the below lines into the code block to import all the necessary files and modules.

import rospy
import actionlib
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
from math import radians, degrees
from actionlib_msgs.msg import *
from geometry_msgs.msg import Point

Next, initialize the rosnode and actionlib.

rospy.init_node("map_navigation", anonymous=False)
ac = actionlib.SimpleActionClient("move_base", MoveBaseAction)

On a separate terminal window, run the below line to get the current position of the robot on the map. The image below is an example output.

$ rostopic echo /amcl_pose

Next, intialize and select an end position for the robot's navigation.

goal = MoveBaseGoal()
goal.target_pose.header.frame_id = "map"
goal.target_pose.header.stamp = rospy.Time.now()
goal.target_pose.pose.position = Point(0.45, -0.777, 0)
goal.target_pose.pose.orientation.x = 0.0
goal.target_pose.pose.orientation.y = 0.0
goal.target_pose.pose.orientation.z = 0.0
goal.target_pose.pose.orientation.w = 0.0

Alternatively, we can determine the angles at which the robot should move at using quaternions

import tf
import math

[p, q, r] = [each*math.pi/180.0 for each in [0, 0, 90]]
x, y, z, w = tf.transformations.quaternion_from_euler(p, q, r)
x, y, z, w

Lastly, we start navigation with the below line.

ac.send_goal(goal)

Video Demonstration

To see a video demonstration of this page, check this video here: https://www.youtube.com/watch?v=mIw8EjJsa9E

Last updated