hi @roalgoal ,
I have just tried again, and shut down my firewall and adblock, but it still doesn’t work. And previously I have tried 2 other computer, they also don’t work. It is always the same problem:
'LaserScan' is not subscriptable
I wonder if there is problem with my account. Or is there some changes I must do in .py code? Before connecting to lab robot, my code works well in simulation. This the code I run on turtlebot, which is from rosject of ‘‘wall follower’’ with the function of ‘‘finding the wall’’:
#! /usr/bin/env python
import rospy
from section_service.srv import FindWall, FindWallResponse
from geometry_msgs.msg import Twist
from sensor_msgs.msg import LaserScan
import numpy as np
import time
class Find_Wall_Service_Server_Class():
def __init__(self):
# define subscriber of laser data from '/scan'
self.scan_sub = rospy.Subscriber(
"/scan", LaserScan, self.sub_callback)
self.laser_data = LaserScan()
# define publisher of velocity command to '/cmd_vel'
self.vel_pub = rospy.Publisher("/cmd_vel", Twist, queue_size=1)
self.vel = Twist()
# define service server '/find_wall'
self.my_Service = rospy.Service(
"/find_wall", FindWall, self.service_callback)
rospy.loginfo("The service: /find_wall is ready")
# define others
self.rate = rospy.Rate(1)
def sub_callback(self, msg):
self.laser_data = msg.ranges
def service_callback(self, request):
rospy.loginfo('robot is looking for the wall......')
###### first step ######
# escape from a corner
wall_point = np.argmin(self.laser_data)
count_of_corner = 0
label_of_corner = False
# split the circle into 4 sectors: [0,180], [181,360], [361,540], [541,720]
# if the robot is in a corner
# and the point which is closest to the wall is settled in sector1
if 0 <= wall_point <= 180:
wall_point_1 = wall_point
wall_point_2 = wall_point + 180
wall_point_3 = wall_point + 360
wall_point_4 = wall_point + 540
# and the point which is closest to the wall is settled in sector2
elif 181 <= wall_point <= 360:
wall_point_1 = wall_point - 180
wall_point_2 = wall_point
wall_point_3 = wall_point + 180
wall_point_4 = wall_point + 360
# and the point which is closest to the wall is settled in sector3
elif 361 <= wall_point <= 540:
wall_point_1 = wall_point - 360
wall_point_2 = wall_point - 180
wall_point_3 = wall_point
wall_point_4 = wall_point + 180
# and the point which is closest to the wall is settled in sector4
elif 541 <= wall_point <= 720:
wall_point_1 = wall_point - 540
wall_point_2 = wall_point - 360
wall_point_3 = wall_point - 180
wall_point_4 = wall_point
# if there is 2 edges has a distance less than 0.2m, then the robot is stuck in a corner
if self.laser_data[wall_point_1] <= 0.2:
count_of_corner += 1
if self.laser_data[wall_point_2] <= 0.2:
count_of_corner += 1
if self.laser_data[wall_point_3] <= 0.2:
count_of_corner += 1
if self.laser_data[wall_point_4] <= 0.2:
count_of_corner += 1
if count_of_corner >= 2:
label_of_corner = True
# if robot is in a corner, then escape firstly
if label_of_corner == True:
rospy.loginfo('count_of_corner = ' + str(count_of_corner))
rospy.loginfo('the robot is stuck in corner......')
# rotate to make the orthometric front direction perpendicular to a wall
wall_point = np.argmin(self.laser_data)
# if robot is back off corner, then move forwards
if 0 <= wall_point <= 180 or 541 <= wall_point <= 720:
self.vel.linear.x = 0.2
self.vel_pub.publish(self.vel)
time.sleep(2)
# if robot is faced with corner, then move backwards
else:
self.vel.linear.x = -0.2
self.vel_pub.publish(self.vel)
time.sleep(2)
self.vel.linear.x = 0
self.vel_pub.publish(self.vel)
time.sleep(1)
###### second step ######
# rotate to find the direction with shortest distance
min_idx = np.argmin(self.laser_data)
# define the angle need to be rotated
angle = min_idx - 360
# clockwise, if shortest direction is on the left
# anti-clockwise, if shortest direction is on the right
# the ranges divided one round with 720 angular grids, each grid is 0.00872rad
while not abs(angle) <= 10:
self.vel.angular.z = 0.00872 * angle
self.vel_pub.publish(self.vel)
time.sleep(1)
# stop robot
self.vel.linear.x = 0
self.vel.angular.z = 0
self.vel_pub.publish(self.vel)
# update min_idx
min_idx = np.argmin(self.laser_data)
angle = min_idx - 360
# stay for a while
time.sleep(1)
###### third step ######
# move to the wall and keep specific distance
self.front_dist = self.laser_data[360]
# if robot is stick to the wall or too close to the wall, move backwards
if self.front_dist == np.inf or self.front_dist < 0.2:
while self.front_dist == np.inf or self.front_dist < 0.2:
self.vel.linear.x = -0.02
self.vel_pub.publish(self.vel)
time.sleep(1)
self.front_dist = self.laser_data[360]
# if robot is too far away from the wall, move forwards
else:
while self.front_dist > 0.2:
self.vel.linear.x = 0.02
self.vel_pub.publish(self.vel)
time.sleep(1)
self.front_dist = self.laser_data[360]
self.vel.linear.x = 0
self.vel.angular.z = 0
self.vel_pub.publish(self.vel)
time.sleep(1)
###### fourth step ######
# rotate to be along with the wall
# roatate 90 degree anticlockwise, making the wall on the right side of the bot
self.vel.angular.z = 0.7
self.vel_pub.publish(self.vel)
time.sleep(4)
self.vel.linear.z = 0
self.vel.angular.z = 0
self.vel_pub.publish(self.vel)
time.sleep(1)
# in order to ensure the final direction of robot
# is along the wall
# change the direction criterion from front(360) to right(180)
min_idx = np.argmin(self.laser_data)
angle = min_idx - 180
# as long as the difference between desired and current direction is more than 3 degree, it is not acceptable
# attention: the ranges is a list of length 720, a.k.a 2 grid unit is 1 radius degree
while not abs(angle) <= 6:
# rotate to adjust the direction in details
self.vel.angular.z = 0.00872 * angle / 2
self.vel_pub.publish(self.vel)
time.sleep(2)
# stop robot
self.vel.linear.x = 0
self.vel.angular.z = 0
self.vel_pub.publish(self.vel)
# update min_idx
min_idx = np.argmin(self.laser_data)
angle = min_idx - 180
# stay for a whilie
time.sleep(3)
###### final step ######
# return message
my_response = FindWallResponse()
my_response.wallfound = True
rospy.loginfo('the wall is found......')
return my_response
def main(self):
rospy.loginfo('the service server is ready')
rospy.loginfo('call the service by: ')
rospy.loginfo('rosservice call /find_wall')
# rospy.spin()
if __name__ == '__main__':
rospy.init_node("find_wall_2_node")
FindWallServiceServer = Find_Wall_Service_Server_Class()
FindWallServiceServer.main()
rospy.spin()
In case my operation may have some errors,these is the order I connect the robot:
- book turtlebot
- when the reservation is coming, the robot-icon with a red point of top-right corner, click it and the point turns green
- and camera can show the robot in the lab, joystick works also well
- then
rostopic list
but it shows cannot communicate with master
please help…