-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathrobot.py
118 lines (78 loc) · 2.93 KB
/
robot.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
# coding=utf-8
from math import radians
import cv2
import rospy
from cv_bridge import CvBridge, CvBridgeError
from gazebo_msgs.msg import ModelStates
from geometry_msgs.msg import Twist
from sensor_msgs.msg import Image
import re
class Robot:
def __init__(self):
rospy.init_node('turtlebot_robot', anonymous=False)
rospy.loginfo("Press ctrl+c to stop!")
rospy.on_shutdown(self.__shutdown)
self.__cmd_vel = rospy.Publisher('cmd_vel_mux/input/navi', Twist, queue_size=10)
self.rate = rospy.Rate(10)
self.turn_cmd = Twist()
self.turn_cmd.linear.x = 0
self.turn_cmd.angular.z = radians(10)
self.move_cmd = Twist()
self.move_cmd.angular.z = radians(0)
self.move_cmd.linear.x = 0.1
self.bridge = CvBridge()
self.image_received = False
self.image_sub = rospy.Subscriber("/camera/rgb/image_raw", Image, self.__recv_image)
self.image = None
self.state_sub = rospy.Subscriber("/gazebo/model_states", ModelStates, self.__recv_states)
self.box_pos = []
rospy.sleep(1)
def set_move_speed(self, met_per_sec):
self.move_cmd.angular.z = 0
self.move_cmd.linear.x = met_per_sec
def set_turn_speed(self, deg_per_sec):
self.turn_cmd.linear.x = 0
self.turn_cmd.angular.z = radians(deg_per_sec)
def go_forward(self, seconds):
times = seconds * 10
for x in xrange(0, times):
self.publish_twist(self.move_cmd)
self.rate.sleep()
rospy.sleep(1)
def turn_around(self, seconds):
times = seconds * 10
for x in xrange(0, times):
self.publish_twist(self.turn_cmd)
self.rate.sleep()
rospy.sleep(1)
def publish_twist(self, twist):
self.__cmd_vel.publish(twist)
def get_image(self):
return self.image
def __recv_image(self, data):
cv_image = None
try:
cv_image = self.bridge.imgmsg_to_cv2(data, "bgr8")
except CvBridgeError as e:
print(e)
self.image_received = True
self.image = cv_image
gray_image = cv2.cvtColor(cv_image, cv2.COLOR_BGR2GRAY)
ret, self.binary_image = cv2.threshold(gray_image, 127, 255, cv2.THRESH_BINARY)
def get_box_position(self):
return self.box_pos
def __recv_states(self, model_states):
reg = 'newbox*'
nameRe = re.compile(reg)
res = []
for i in xrange(len(model_states.name)):
if nameRe.match(model_states.name[i]):
x = float(model_states.pose[i].position.x)
y = float(model_states.pose[i].position.y)
res.append((x, y))
self.box_pos = res
pass
def __shutdown(self):
rospy.loginfo("Stop the turtlebot")
self.__cmd_vel.publish(Twist())
rospy.sleep(1)