ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Extract angles from a lidar in turtlebot3

asked 2022-10-03 04:57:49 -0500

kimsolphin gravatar image

updated 2022-10-04 05:28:34 -0500

ravijoshi gravatar image

A goal of mine is to detect an object from 1.0[m] to 1.5[m], using a lidar, and send angle information to another node. I’m on elementary level of making a code. So, if you help me, It’s going to be really helpful. I want a code that can apply my project.

edit retag flag offensive close merge delete

Comments

1

You should subscribe to the lidar messages. Inside the callback, iterate over the message accordingly. Please read Writing a Simple Subscriber (C++).

ravijoshi gravatar image ravijoshi  ( 2022-10-04 05:28:16 -0500 )edit

Sir, I understand how to make nodes, but how can I access to lidar data? Could you explain me in detail? Thanks for your help

kimsolphin gravatar image kimsolphin  ( 2022-10-06 10:03:39 -0500 )edit

1 Answer

Sort by » oldest newest most voted
1

answered 2022-10-07 01:31:12 -0500

ravijoshi gravatar image

I understand how to make nodes, but how can I access to lidar data ...

This sentence is confusing in a sense. Anyway, let's break your problem into pieces and solve them:

  1. detect an object from 1.0[m] to 1.5[m], using a lidar

    To do this task, we need to create a subscriber first, and then inside the callback, we can pick the angles based on our criteria. In this case, the criteria is the distance of the object.

  2. send angle information to another node

    To do this task, we need to create a publisher that can publish the angle data. Then, the published data can be acquired by other nodes easily.

Please see the complete code below:

#!/usr/bin/env python
# -*- coding: utf-8 -*-

import rospy
from sensor_msgs.msg import LaserScan
from std_msgs.msg import Float32MultiArray

pub = rospy.Publisher('/detected_object', Float32MultiArray, queue_size=1)


def callback(msg):
    # let's define a range
    distance_min = 1.0
    distance_max = 1.5

    result = Float32MultiArray()
    for i, r in enumerate(msg.ranges):
        # we need object in 1 to 1.5 m range
        if distance_min < r < distance_max:
            angle = msg.angle_min + i * msg.angle_increment
            result.data.append(angle)
    pub.publish(result)


def objectDetector():
    rospy.init_node('object_detector', anonymous=True)
    rospy.Subscriber('/base_scan', LaserScan, callback)
    rospy.spin()


if __name__ == '__main__':
    objectDetector()

I used a recorded bag file file mentioned in this wiki page to run the above code. Please see below an example: Please see below a demonstration:

$ rosrun my_package object_detector.py 
$ rostopic echo /detected_object
layout: 
  dim: []
  data_offset: 0
data: [0.5559560656547546, 0.608904242515564]
---
layout: 
  dim: []
  data_offset: 0
data: [0.5559560656547546, 0.608904242515564]
---
layout: 
  dim: []
  data_offset: 0
data: [0.5030078887939453, 0.5559560656547546]
---

To understand the definition of sensor_msgs/LaserScan message, please see here.

edit flag offensive delete link more

Comments

Sir, I really appriciate you, even if I'm in elementary level, I want to be like you in the future. ありがとうございます.

kimsolphin gravatar image kimsolphin  ( 2022-10-08 09:08:07 -0500 )edit
1

Thanks for your kind words. Did the answer solve your problem? If yes, kindly upvote and click "mark this answer as correct" to tag this question as answered.

ravijoshi gravatar image ravijoshi  ( 2022-10-08 09:46:18 -0500 )edit

I'm sorry that I saw your comment late , I just clicked upvote and 'mark this answer as correct'. Thanks,sir

kimsolphin gravatar image kimsolphin  ( 2022-10-31 02:39:45 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2022-10-03 04:57:49 -0500

Seen: 55 times

Last updated: Oct 07 '22