def pulse(sign): bot = Robot() bot.playNote('A4', 5) bot.setTurnSpeed(30 * sign) time.sleep(0.1) bot.setTurnSpeed(0) bot.close()
def main(): #establish robot connection bot = Robot() bot.playNote('A4', 50) # establish control connection host = "10.7.88.88" port = 9000 s = socket.socket() s.bind((host, port)) s.listen(1) client_socket, client_address = s.accept() print("Connection established from: " + str(client_address)) # the received message last_message = 'i' while 1: data = client_socket.recv(2).decode('utf-8') datac = [char for char in data] print(data) # Stop the robot when no target is detected if datac[0] == 's': bot.setForwardSpeed(0) if datac[1] == 's': bot.setTurnSpeed(0) # set the iRobot to go forward if datac[0] == 'f': bot.setForwardSpeed(100) time.sleep(1) bot.setForwardSpeed(0) # set the iRobot to turn left elif datac[1] == 'l': bot.setTurnSpeed(25) time.sleep(1) bot.setTurnSpeed(0) # set the iRobot to turn right elif datac[1] == 'r': bot.setTurnSpeed(-25) time.sleep(1) bot.setTurnSpeed(0) last_message = datac client_socket.close() bot.close() pipeline.stop()
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. ''' from breezycreate2 import Robot import time # Create a Create2. This will automatically try to connect to your robot over serial bot = Robot(250, 100, "COM3") # bot.initGrid(1,0,90) # bot.gridMoveTo(0,0) # bot.gridMoveTo(-1,0) # bot.gridMoveTo(2,2) # bot.gridMoveTo(1,0) # bot.gridMoveTo(0,-2) # bot.gridMoveTo(0,0) # bot.gridMoveTo(2.5,1.25) # Report bumper hits and wall proximity for 30 seconds # start_time = time.time() # while (time.time() - start_time) < 10: # print('Bumpers: ' + str(bot.getBumpers()) + ' Wall: ' + str(bot.getWallSensor())) # Close the connection bot.close()
class IRobotProcessing(): def __init__(self): self.__vr = 0 self.__vl = 0 self.bot = Robot() # Open the robot def setVR(self, vr): self.__vr = vr # Setup the speed of right wheel def setVL(self, vl): self.__vl = vl # Setup the speed of left wheel def getVR(self): return self.__vr def getVL(self): return self.__vl # Let the robot move by this class data def run(self): self.bot.setWheelSpeed(self.__vr, self.__vl) # Let the robot move by the other class argument def move(self, vr, vl): self.bot.setWheelSpeed(vr, vl) # Turn off the wheel motors. def stop(self): self.bot.setWheelSpeed(0, 0) # Turn off the robot def close(self): self.bot.close() # reset all the internal data of the robot. def reset(self): self.bot.reset() def getDistanceAngle(self, pre_right_encoder, pre_left_encoder): right_encoder, left_encoder = self.getEncoder() difference_right = right_encoder - pre_right_encoder difference_left = left_encoder - pre_left_encoder # right_distance = difference_right / 508.8 * np.pi * 72 # left_distance = difference_left / 508.8 * np.pi * 72 # Formula for iRobot Create2: # Distance: (current encoder - pre encodeer) / 508.8 * pi * 72 # Angle: (right distance - left ddstance)/ 235.0 # Note: When the encoder counted to 65536 (2^16), the encoder will count back to O if difference_right > 60000: right_distance = ((right_encoder - 65536) - pre_right_encoder) / 508.8 * np.pi * 72 elif difference_right < -60000: right_distance = ((65536 - pre_right_encoder) + right_encoder) / 508.8 * np.pi * 72 else: right_distance = difference_right / 508.8 * np.pi * 72 if difference_left > 60000: left_distance = ( (left_encoder - 65536) - pre_left_encoder) / 508.8 * np.pi * 72 elif difference_left < -60000: left_distance = ( (65536 - pre_left_encoder) + left_encoder) / 508.8 * np.pi * 72 else: left_distance = difference_left / 508.8 * np.pi * 72 angle = math.degrees((right_distance - left_distance) / 235.0) distance = (right_distance + left_distance) / 2 return distance, angle, right_distance, left_distance, right_encoder, left_encoder def getEncoder(self): right_encoder, left_encoder = self.bot.getEncoderCounts() ''' if vr < 0: right_encoder = 65536 - right_encoder if vl < 0: left_encoder = 65536 - left_encoder ''' print "right encoder: " + str(right_encoder) print "left encoder: " + str(left_encoder) return right_encoder, left_encoder def lineFollowing(self, status, expectation_distance, pre_cx, cx, rotation_direction, small_distance, angle): # status: check whether there are horizontal lines in images and the robot close to the node(corner). 1 means both of them are ture. # expectation_distance: The distance the robot need to move when close the the node. # pre_cx: the pre center of the contour # cx: the current center of the contour # small_distance: use to compare with the expectation_distance if status == 1: if small_distance < expectation_distance: self.setVR(15) self.setVL(15) self.run() else: self.setVR(0) self.setVL(0) self.run() status = 0 ''' if angle >= 85 or angle < -85: status = 0 distance = 0 angle = 0 ''' else: if cx == -1: print 'Out of track' ''' if rotation_direction < 0 or pre_cx < 320: self.setVR(15) self.setVL(-15) self.run() elif rotation_direction > 0 or pre_cx > 320: self.setVR(-15) self.setVL(15) self.run() else: self.setVR(15) self.setVL(15) self.run() ''' if angle > 0: self.setVR(15) self.setVL(-15) self.run() else: self.setVR(-15) self.setVL(15) self.run() else: if cx >= 340 and cx < 440: self.setVR(5) self.setVL(20) self.run() print 'Turning right' # time.sleep(3) # bot.setTurnSpeed(0) # time.sleep(2) elif cx >= 440: self.setVR(5) self.setVL(25) self.run() print "Turning right" elif cx < 340 and cx > 300: if rotation_direction > 0: self.setVR(20) self.setVL(5) self.run() elif rotation_direction < 0: self.setVR(5) self.setVL(25) self.run() else: self.setVR(40) self.setVL(40) self.run() print 'Going forward' # time.sleep(1) # bot.setTurnSpeed(0) # time.sleep(2) elif cx <= 300 and cx > 200: self.setVR(20) self.setVL(5) self.run() print 'Turning left' # time.sleep(3) # bot.setTurnSpeed(0) # time.sleep(2) elif cx <= 200: self.setVR(25) self.setVL(5) self.run() print "Turning left" if cx != -1: return cx, status else: return pre_cx, status
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. ''' from breezycreate2 import Robot import time # Create a Create2. This will automatically try to connect to your robot over serial bot = Robot() # Play a note to let us know you're alive! bot.playNote('A4', 100) # Tell the Create2 to turn right slowly bot.setTurnSpeed(-50) # Wait a second time.sleep(1) # Stop bot.setTurnSpeed(0) # Report bumper hits and wall proximity for 30 seconds start_time = time.time() while (time.time() - start_time) < 30: print('Bumpers: ' + str(bot.getBumpers()) + ' Wall: ' + str(bot.getWallSensor())) # Close the connection bot.close()