[ROS Q&A] 140 – How to Modify a Robot’s Coordinates When it Arrives at a Checkpoint?

[ROS-Q&A]-140---How-to-Modify-a-Robot's-Coordinates-When-it-Arrives-at-a-Checkpoint-

Written by Arif Rahman

18/07/2018


In this video we are going to see how to programmatically modify a robot’s coordinates when it arrives at a known checkpoint. We will use the same technique as clicking on the 2D Pose Estimate in RViz, but with a Python script. This is useful for the robot to know its exact location whenever it arrives at a checkpoint.

This is a video trying to answer the following question posted at the ROS answers forum.

Step 1. Create a project in ROS Development Studio(ROSDS)

ROSDS helps you follow our tutorial in a fast pace without dealing without setting up an environment locally. If you haven’t had an account yet, you can create a free account here.

Step 2. Start simulation

In this post, we’re going to start bt running turtlebot navigation simulation first with the following commands. Please open an empty gazebo simulation environment from tools->gazebo and then execute the commands in 3 different shells(you can find them in Tools->Shell).

roslaunch turtlebot_navigation_gazebo main.launch

This command spawns the turtlebot and world in gazebo

roslaunch turtlebot_navigation_gazebo move_base_demo.launch

The second command launch the amcl algorithm for the turtlebot

roslaunch turtlebot_rviz_launchers view_navigation.launch

The third one launches the rviz tool for visualization. You can open the graphical window from Tools->graphical tools.

Step 3. Create a new package for the task

In rviz, you can click 2D post Estimate button to estimate the current location of the robot. Our idea is whenever the robot detects a RFID, it will update it’s current location. When you click the button, it publishes a message for you to the topic /initialpose. To check the type of the message, type rostopic info /initialpost , you’ll see that the message type is geometry_msgs/PoseWithCovarianceStamped. If we want to update the pose, we have to be able to send this message.

Let’s create a package to do this task.

cd ~/catkin_ws/src
catkin_create_pkg set_point rospy

Under the package directory, create a script folder and put our script called main.py inside it with the following content

#!/usr/bin/env python

import rospy
from geometry_msgs.msg import PoseWithCovarianceStamped
from tf.transformations import quaternion_from_euler

rospy.init_node('init_pos')
pub = rospy.Publisher('/initialpose', PoseWithCovarianceStamped, queue_size = 10)
rospy.sleep(3)
checkpoint = PoseWithCovarianceStamped()

checkpoint.pose.pose.position.x = 0.0
checkpoint.pose.pose.position.y = 0.0
checkpoint.pose.pose.position.z = 0.0

[x,y,z,w]=quaternion_from_euler(0.0,0.0,0.0)
checkpoint.pose.pose.orientation.x = x
checkpoint.pose.pose.orientation.y = y
checkpoint.pose.pose.orientation.z = z
checkpoint.pose.pose.orientation.w = w

print checkpoint
pub.publish(checkpoint)

In this script, we set the initial point to x,y,z all equal to zero. If you run the script, you’ll see that the robot model moves to the origin of the map!

 

 

Edit by: Tony Huang

 

// RELATED LINKS

▸ Original question: https://answers.ros.org/question/278551/how-do-i-modifychange-base_footprint-by-program/
▸ ROS Development Studio (RDS): https://goo.gl/bUFuAq
▸ Robot Ignite Academy: https://goo.gl/6nNwhs


Feedback

Did you like this video? Do you have questions about what is explained? Whatever the case, please leave a comment on the comments section below, so we can interact and learn from each other.

If you want to learn about other ROS topics, please let us know on the comments area and we will do a video about it.

Topics:
Masterclass 2023 batch2 blog banner

Check Out These Related Posts

129. ros2ai

129. ros2ai

I would like to dedicate this episode to all the ROS Developers who believe that ChatGPT or...

read more

0 Comments

Submit a Comment

Your email address will not be published.

This site uses Akismet to reduce spam. Learn how your comment data is processed.

Pin It on Pinterest

Share This