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

ros node to follow walls to solve a maze.How to subscribe to LaserScan?

asked 2016-10-31 01:45:06 -0500

Shubhayu Das gravatar image

updated 2016-10-31 02:07:24 -0500

ahendrix gravatar image

#!/usr/bin/env python

import rospy
from geometry_msgs.msg import Twist
from sensor_msgs.msg import LaserScan
from std_msgs.msg import Float32

class wall_follow():

    def __init__(self,r1=0.0,r2=0.0,threshold=5.0,i=0):
      self.r1=r1
      self.r2=r2
      self.threshold=threshold
      self.i=i
      rospy.init_node('wall_follow',anonymous=True) 
      rospy.loginfo("Press Ctrl+C to Exit")
      rospy.on_shutdown(self.shutdown)
      self.cmd_vel = rospy.Publisher('cmd_vel_mux/input/navi', Twist, queue_size=50)
      rate = rospy.Rate(.5)
      while not rospy.is_shutdown():
        rospy.loginfo("%g",self.i)
        self.i=self.i+1
        move_cmd=Twist()
        self.sub=rospy.Subscriber('scan',LaserScan,self.wall_info)
        ros.loginfo("range_1080 = %g range_720 = %g", self.r1,self.r2)
        if self.r2-self.r1 > self.threshold:
            move_cmd.angular.z=1.0
            move_cmd.linear.x=0.0
        elif self.r2-self.r1 < -1*self.threshold:
            move_cmd.angular.z=-1.0
            move_cmd.linear.x=0.0
        else:
            move_cmd.angular.z=0.0
            move_cmd.linear.x=0.3
        self.cmd_vel.publish(move_cmd)
        rate.sleep()    

    def wall_info(self,scan):
      self.r1=scan.ranges[1080]
      self.r2=scan.ranges[720]
      rospy.spin()

    def shutdown(self): 
      rospy.loginfo("Stopping TurtleBot")
      self.cmd_vel.publish(Twist())
      # Give TurtleBot time to stop
      rospy.sleep(1)

if __name__ == '__main__':
  try:
    wall_follow()
  except:
    rospy.loginfo("End of the trip for TurtleBot")

The is my Latest code for wall follower node.Logically the bot should move along its left wall(when placed near the left wall of maze entry point). But when I run this code on my turtlebot, I don't get any error, however it doesn't move. This is all I see :

[INFO] [WallTime: 1477891660.282792] Press Ctrl+C to Exit [INFO] [WallTime: 1477891660.298116] 0 [INFO] [WallTime: 1477891660.320208] End of the trip for TurtleBot [INFO] [WallTime: 1477891660.436050] Stopping TurtleBot

Clearly since the first index i=0 is getting printed, the scope is entering the while loop, but is not carrying on. Since I am very new with ros I am not sure it this is a syntactical error, or perhaps a problem with the " self.sub=rospy.Subscriber('scan',LaserScan,self.wall_info) " statement, or the wall_info(self,scan) function.

Please Help.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2016-10-31 02:10:44 -0500

ahendrix gravatar image

The first message you see is End of the trip for TurtleBot , which indicates that your code is going into the except section at the last 5 lines of your code:

if __name__ == '__main__':
  try:
    wall_follow()
  except:
    rospy.loginfo("End of the trip for TurtleBot")

Since this is getting into the except block, it means that there's some kind of exception being thrown in wall_follow(). I'd recommend that you either print the exception that's thrown, or remove the try/except block so that you can see where this exception is coming from.

edit flag offensive delete link more

Comments

Thank you for the reply. I have updated the code. The problem there was that I wasn't running "rosrun hokuyo_node hokuyo_node" Sorry of the armature work. But i am still getting a error. Pls Check out my next post / question

Shubhayu Das gravatar image Shubhayu Das  ( 2016-10-31 04:24:37 -0500 )edit
0

answered 2016-10-31 04:38:44 -0500

Shubhayu Das gravatar image

Here is an updated version..

#!/usr/bin/env python

import rospy from geometry_msgs.msg import Twist from sensor_msgs.msg import LaserScan

class wall_follow():

def __init__(self,r1=0.0,r2=0.0,threshold=5.0,i=0):
  self.r1=r1
  self.r2=r2
  self.threshold=threshold
  self.i=i
  rospy.init_node('wall_follow', anonymous=True) 
  rospy.loginfo("Press Ctrl+C to Exit")
  rospy.on_shutdown(self.shutdown)
  self.cmd_vel = rospy.Publisher('cmd_vel_mux/input/navi', Twist, queue_size=50)
  self.sub=rospy.Subscriber('scan',LaserScan,self.scan_callback)
  rate = rospy.Rate(.5)
  while not rospy.is_shutdown():
    rospy.loginfo("%d",self.i)
    self.i=self.i+1
    move_cmd=Twist()

    rospy.loginfo("range_580 = %f range_500 = %f", self.r1,self.r2)

    if self.r2-self.r1 > self.threshold:
        move_cmd.angular.z=1.0
        move_cmd.linear.x=0.0
    elif self.r2-self.r1 < -1*self.threshold:
        move_cmd.angular.z=-1.0
        move_cmd.linear.x=0.0
    else:
        move_cmd.angular.z=0.0
        move_cmd.linear.x=0.3
    self.cmd_vel.publish(move_cmd)
    rate.sleep()    
def scan_callback(self,msg):
  rospy.loginfo("%d",self.i)
  self.r1=msg.ranges[580]
  self.r2=msg.ranges[500]
  rospy.spin()

def shutdown(self): 
  rospy.loginfo("Stopping TurtleBot")
  self.cmd_vel.publish(Twist())
  # Give TurtleBot time to stop
  rospy.sleep(1)

if __name__ == '__main__': try: wall_follow() except: rospy.loginfo("End of the trip for TurtleBot")


As you can see changed the position of the Subscriber callback outside, i tried placing inside as well still the algo is not working. I am getting the following result

[INFO] [WallTime: 1477906023.974810] Press Ctrl+C to Exit [INFO] [WallTime: 1477906023.985877] 0 [INFO] [WallTime: 1477906024.005692] range_580 = 0.000000 range_500 = 0.000000 [INFO] [WallTime: 1477906024.113967] 1 [ERROR] [WallTime: 1477906024.116318] bad callback: <bound method="" wall_follow.scan_callback="" of="" <__main__.wall_follow="" instance="" at="" 0x7fac758c9998="">> Traceback (most recent call last): File "/opt/ros/indigo/lib/python2.7/dist-packages/rospy/topics.py", line 720, in _invoke_callback cb(msg) File "wall_follower.py", line 41, in scan_callback self.r1=msg.ranges[580] IndexError: tuple index out of range

[INFO] [WallTime: 1477906024.213830] 1 [ERROR] [WallTime: 1477906024.215866] bad callback: <bound method="" wall_follow.scan_callback="" of="" <__main__.wall_follow="" instance="" at="" 0x7fac758c9998="">> Traceback (most recent call last): File "/opt/ros/indigo/lib/python2.7/dist-packages/rospy/topics.py", line 720, in _invoke_callback cb(msg) File "wall_follower.py", line 41, in scan_callback self.r1=msg.ranges[580] IndexError: tuple index out of range

#..... and so on

each time value of i is incremented, the bot moves one unit forward.


the value of ranges is not changing!! I checked the hokuyo model specs (it can scan upto 240_deg with each step of about 3.52_deg) so the index 580 should be within its limit.

Please Help.

Also, if you could advise / share any other approach to this problem, it would be very nice.

edit flag offensive delete link more

Comments

Obviously 580 is not within the limits of the data returned by the laser scanner. You may want to check the starting and ending angle of the scan range to make sure that your sensor is configured properly.

ahendrix gravatar image ahendrix  ( 2016-10-31 12:58:29 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-10-31 01:31:56 -0500

Seen: 2,259 times

Last updated: Oct 31 '16