/
robot_control_class.py
143 lines (110 loc) · 3.9 KB
/
robot_control_class.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
#!/usr/bin/env python
import rospy
from geometry_msgs.msg import Twist
from sensor_msgs.msg import LaserScan
import time
class RobotControl():
def __init__(self):
rospy.init_node('robot_control_node', anonymous=True)
self.vel_publisher = rospy.Publisher('/cmd_vel', Twist, queue_size=1)
self.laser_subscriber = rospy.Subscriber(
'/kobuki/laser/scan', LaserScan, self.laser_callback)
self.cmd = Twist()
self.laser_msg = LaserScan()
self.ctrl_c = False
self.rate = rospy.Rate(1)
rospy.on_shutdown(self.shutdownhook)
def publish_once_in_cmd_vel(self):
"""
This is because publishing in topics sometimes fails the first time you publish.
In continuos publishing systems there is no big deal but in systems that publish only
once it IS very important.
"""
while not self.ctrl_c:
connections = self.vel_publisher.get_num_connections()
if connections > 0:
self.vel_publisher.publish(self.cmd)
#rospy.loginfo("Cmd Published")
break
else:
self.rate.sleep()
def shutdownhook(self):
# works better than the rospy.is_shutdown()
self.ctrl_c = True
def laser_callback(self, msg):
self.laser_msg = msg
def get_laser(self, pos):
time.sleep(1)
return self.laser_msg.ranges[pos]
def get_front_laser(self):
time.sleep(1)
return self.laser_msg.ranges[360]
def get_laser_full(self):
time.sleep(1)
return self.laser_msg.ranges
def stop_robot(self):
#rospy.loginfo("shutdown time! Stop the robot")
self.cmd.linear.x = 0.0
self.cmd.angular.z = 0.0
self.publish_once_in_cmd_vel()
def move_straight(self):
# Initilize velocities
self.cmd.linear.x = 0.5
self.cmd.linear.y = 0
self.cmd.linear.z = 0
self.cmd.angular.x = 0
self.cmd.angular.y = 0
self.cmd.angular.z = 0
# Publish the velocity
self.publish_once_in_cmd_vel()
def move_straight_time(self, motion, speed, time):
# Initilize velocities
self.cmd.linear.y = 0
self.cmd.linear.z = 0
self.cmd.angular.x = 0
self.cmd.angular.y = 0
self.cmd.angular.z = 0
if motion == "forward":
self.cmd.linear.x = speed
elif motion == "backward":
self.cmd.linear.x = - speed
i = 0
# loop to publish the velocity estimate, current_distance = velocity * (t1 - t0)
while (i <= time):
# Publish the velocity
self.vel_publisher.publish(self.cmd)
i += 1
self.rate.sleep()
# set velocity to zero to stop the robot
self.stop_robot()
s = "Moved robot " + motion + " for " + str(time) + " seconds"
return s
def turn(self, clockwise, speed, time):
# Initilize velocities
self.cmd.linear.x = 0
self.cmd.linear.y = 0
self.cmd.linear.z = 0
self.cmd.angular.x = 0
self.cmd.angular.y = 0
if clockwise == "clockwise":
self.cmd.angular.z = -speed
else:
self.cmd.angular.z = speed
i = 0
# loop to publish the velocity estimate, current_distance = velocity * (t1 - t0)
while (i <= time):
# Publish the velocity
self.vel_publisher.publish(self.cmd)
i += 1
self.rate.sleep()
# set velocity to zero to stop the robot
self.stop_robot()
s = "Turned robot " + clockwise + " for " + str(time) + " seconds"
return s
if __name__ == '__main__':
#rospy.init_node('robot_control_node', anonymous=True)
robotcontrol_object = RobotControl()
try:
robotcontrol_object.move_straight()
except rospy.ROSInterruptException:
pass