Exploring ROS with a 2 Wheeled Robot #4 – Laser Scan Reading

Laser Scan Reading

Written by Marco Arruda

04/05/2019

Hello ROS Developers!

In this post, we summarize the video – Exploring ROS using a 2 Wheeled Robot ep. 4, where we start using the Laser Scan data. Let’s start!

First thing, let’s open our ROSject finished with the previous post.

We had some minor adjustments (in order to calibrate the robot and fix some minor issues), that you can track here. They are the following:

  • Adjust robot size and calibrate differential drive
  • Update CMakeLists.txt
  • Create a world file, that we are going to use in the next episodes
  • Create a launch file to start the world

The ROSject we finished in the last post is this one, but, in order to get the one updated (with the fixed I mentioned), click here.

You must be able to launch a simulation like below:

 

After that, let’s start with the laser part!

Let’s start creating a new package, but this time at catkin_ws. This is because we are not creating a simulation, instead it’s a motion planning package, that will be able to command any kind of mobile robot! It’s important to understand we are not developing a package strict to our robot, but something generic.

In a web shell, execute the following:

user:~$ cd ~/catkin_ws/src/
user:~$ catkin_create_pkg motion_plan std_msgs geometry_msgs rospy sensor_msgs

And create our first script that interacts with the laser data> ~/catkin_ws/src/motion_plan/scripts/reading_laser.py:

#! /usr/bin/env python

import rospy

from sensor_msgs.msg import LaserScan

def clbk_laser(msg):
    # 720 / 5 = 144
    regions = [
        min(min(msg.ranges[0:143]), 10),
        min(min(msg.ranges[144:287]), 10),
        min(min(msg.ranges[288:431]), 10),
        min(min(msg.ranges[432:575]), 10),
        min(min(msg.ranges[576:713]), 10),
    ]
    rospy.loginfo(regions)

def main():
    rospy.init_node('reading_laser')

    sub = rospy.Subscriber('/m2wr/laser/scan', LaserScan, clbk_laser)

    rospy.spin()

if __name__ == '__main__':
    main()

Using a web shell, spawn the robot in the simulation we have running:

user:~$ roslaunch m2wr_description spawn.launch

With the spawning process finished, start the new script we`ve just created:

user:~$ rosrun motion_plan reading_laser.py

You shall see an output like the below:

[INFO] [1556996996.074220, 1870.728000]: [10, 8.899812698364258, 1.7639966011047363, 0.9439168572425842, 0.8716692924499512]
[INFO] [1556996996.127200, 1870.781000]: [10, 8.92310905456543, 1.7670421600341797, 0.9425056576728821, 0.8715123534202576]
[INFO] [1556996996.176019, 1870.830000]: [10, 8.915216445922852, 1.770876407623291, 0.9503755569458008, 0.8712261319160461]
[INFO] [1556996996.226823, 1870.881000]: [10, 8.923232078552246, 1.7670140266418457, 0.942345380783081, 0.8683222532272339]
[INFO] [1556996996.277591, 1870.931000]: [10, 8.91376781463623, 1.7766363620758057, 0.945663332939148, 0.8739328980445862]
[INFO] [1556996996.327826, 1870.981000]: [10, 8.925933837890625, 1.7535350322723389, 0.954210638999939, 0.8760458827018738]
[INFO] [1556996996.378767, 1871.031000]: [10, 8.916155815124512, 1.7713392972946167, 0.9581797122955322, 0.866176962852478]
[INFO] [1556996996.428421, 1871.081000]: [10, 8.912318229675293, 1.7645303010940552, 0.9598914384841919, 0.8663960695266724]
[INFO] [1556996996.478520, 1871.130000]: [10, 8.918071746826172, 1.786738634109497, 0.9538688659667969, 0.8684337139129639]
[INFO] [1556996996.529212, 1871.180000]: [10, 8.918127059936523, 1.7791880369186401, 0.9522199034690857, 0.8771331906318665]

This is a print of an array which contains 5 means of the laser, summarized in the image below:

You can move the robot using `cmd_vel` or using gazebo drag tool in order to see the values changing. In the image below we have the bottom of a shell under the gazebo window. You can check the 5th position of the array represents the area on the left side of the robot. In the other side, we have maximum value being read: 10 meters, on the right side of the robot.

In case something went wrong up to here, you can get a copy of the final version of this post here.

Feel free to explore the code, navigate using teleop or a custom node. In the next post, we’ll work on an algorithm to make the robot avoid obstacles in the world!

 

Cheers!

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