from roboclaw import Roboclaw from time import sleep roboclaw = Roboclaw("/dev/ttyS0", 38400) roboclaw.Open() # Read encoder motor_1_count = roboclaw.ReadEncM1(0x80) print "Original:" print motor_1_count sleep(2) # Set encoder and then read and print to test operation roboclaw.SetEncM1(0x80, 10000) motor_1_count = roboclaw.ReadEncM1(0x80) print "After setting count:" print motor_1_count sleep(2) # Reset encoders and read and print value to test operation roboclaw.ResetEncoders(0x80) motor_1_count = roboclaw.ReadEncM1(0x80) print "After resetting:" print motor_1_count sleep(2) # Position motor, these values may have to be changed to suit the motor/encoder combination in use
class RoboclawWrapper(object): """Interface between the roboclaw motor drivers and the higher level rover code""" def __init__(self): rospy.loginfo( "Initializing motor controllers") # initialize attributes self.rc = None self.err = [None] * 5 self.address = [] self.current_enc_vals = None self.mutex = False self.roboclaw_mapping = rospy.get_param('~roboclaw_mapping') self.encoder_limits = {} self.establish_roboclaw_connections() self.killMotors() # don't move at start self.setup_encoders() # save settings to non-volatile (permanent) memory for address in self.address: self.rc.WriteNVM(address) for address in self.address: self.rc.ReadNVM(address) self.corner_max_vel = 1000 self.corner_accel = 2000 self.roboclaw_overflow = 2**15-1 accel_max = 655359 accel_rate = 0.5 self.accel_pos = int((accel_max /2) + accel_max * accel_rate) self.accel_neg = int((accel_max /2) - accel_max * accel_rate) self.errorCheck() self.killMotors() # set up publishers and subscribers self.corner_cmd_sub = rospy.Subscriber("/cmd_corner", CommandCorner, self.corner_cmd_cb, queue_size=1) self.drive_cmd_sub = rospy.Subscriber("/cmd_drive", CommandDrive, self.drive_cmd_cb, queue_size=1) self.enc_pub = rospy.Publisher("/encoder", JointState, queue_size=1) self.status_pub = rospy.Publisher("/status", Status, queue_size=1) def run(self): """Blocking loop which runs after initialization has completed""" rate = rospy.Rate(5) mutex_rate = rospy.Rate(10) status = Status() counter = 0 while not rospy.is_shutdown(): while self.mutex and not rospy.is_shutdown(): mutex_rate.sleep() self.mutex = True # read from roboclaws and publish try: self.read_encoder_values() self.enc_pub.publish(self.current_enc_vals) except AssertionError as read_exc: rospy.logwarn( "Failed to read encoder values") if (counter >= 10): status.battery = self.getBattery() status.temp = self.getTemp() status.current = self.getCurrents() status.error_status = self.getErrors() self.status_pub.publish(status) counter = 0 self.mutex = False counter += 1 rate.sleep() def establish_roboclaw_connections(self): """ Attempt connecting to the roboclaws :raises Exception: when connection to one or more of the roboclaws is unsuccessful """ self.rc = Roboclaw(rospy.get_param('/motor_controller/device', "/dev/serial0"), rospy.get_param('/motor_controller/baud_rate', 115200)) self.rc.Open() address_raw = rospy.get_param('motor_controller/addresses') address_list = (address_raw.split(',')) self.address = [None]*len(address_list) for i in range(len(address_list)): self.address[i] = int(address_list[i]) # initialize connection status to successful all_connected = True for address in self.address: rospy.logdebug("Attempting to talk to motor controller ''".format(address)) version_response = self.rc.ReadVersion(address) connected = bool(version_response[0]) if not connected: rospy.logerr("Unable to connect to roboclaw at '{}'".format(address)) all_connected = False else: rospy.logdebug("Roboclaw version for address '{}': '{}'".format(address, version_response[1])) if all_connected: rospy.loginfo("Sucessfully connected to RoboClaw motor controllers") else: raise Exception("Unable to establish connection to one or more of the Roboclaw motor controllers") def setup_encoders(self): """Set up the encoders""" for motor_name, properties in self.roboclaw_mapping.iteritems(): if "corner" in motor_name: enc_min, enc_max = self.read_encoder_limits(properties["address"], properties["channel"]) self.encoder_limits[motor_name] = (enc_min, enc_max) else: self.encoder_limits[motor_name] = (None, None) self.rc.ResetEncoders(properties["address"]) def read_encoder_values(self): """Query roboclaws and update current motors status in encoder ticks""" enc_msg = JointState() enc_msg.header.stamp = rospy.Time.now() for motor_name, properties in self.roboclaw_mapping.iteritems(): enc_msg.name.append(motor_name) position = self.read_encoder_position(properties["address"], properties["channel"]) velocity = self.read_encoder_velocity(properties["address"], properties["channel"]) current = self.read_encoder_current(properties["address"], properties["channel"]) enc_msg.position.append(self.tick2position(position, self.encoder_limits[motor_name][0], self.encoder_limits[motor_name][1], properties['ticks_per_rev'], properties['gear_ratio'])) enc_msg.velocity.append(self.qpps2velocity(velocity, properties['ticks_per_rev'], properties['gear_ratio'])) enc_msg.effort.append(current) self.current_enc_vals = enc_msg def corner_cmd_cb(self, cmd): r = rospy.Rate(10) rospy.logdebug("Corner command callback received: {}".format(cmd)) while self.mutex and not rospy.is_shutdown(): r.sleep() self.mutex = True # convert position to tick encmin, encmax = self.encoder_limits["corner_left_front"] left_front_tick = self.position2tick(cmd.left_front_pos, encmin, encmax, self.roboclaw_mapping["corner_left_front"]["ticks_per_rev"], self.roboclaw_mapping["corner_left_front"]["gear_ratio"]) encmin, encmax = self.encoder_limits["corner_left_back"] left_back_tick = self.position2tick(cmd.left_back_pos, encmin, encmax, self.roboclaw_mapping["corner_left_back"]["ticks_per_rev"], self.roboclaw_mapping["corner_left_back"]["gear_ratio"]) encmin, encmax = self.encoder_limits["corner_right_back"] right_back_tick = self.position2tick(cmd.right_back_pos, encmin, encmax, self.roboclaw_mapping["corner_right_back"]["ticks_per_rev"], self.roboclaw_mapping["corner_right_back"]["gear_ratio"]) encmin, encmax = self.encoder_limits["corner_right_front"] right_front_tick = self.position2tick(cmd.right_front_pos, encmin, encmax, self.roboclaw_mapping["corner_right_front"]["ticks_per_rev"], self.roboclaw_mapping["corner_right_front"]["gear_ratio"]) self.send_position_cmd(self.roboclaw_mapping["corner_left_front"]["address"], self.roboclaw_mapping["corner_left_front"]["channel"], left_front_tick) self.send_position_cmd(self.roboclaw_mapping["corner_left_back"]["address"], self.roboclaw_mapping["corner_left_back"]["channel"], left_back_tick) self.send_position_cmd(self.roboclaw_mapping["corner_right_back"]["address"], self.roboclaw_mapping["corner_right_back"]["channel"], right_back_tick) self.send_position_cmd(self.roboclaw_mapping["corner_right_front"]["address"], self.roboclaw_mapping["corner_right_front"]["channel"], right_front_tick) self.mutex = False def drive_cmd_cb(self, cmd): r = rospy.Rate(10) rospy.logdebug("Drive command callback received: {}".format(cmd)) while self.mutex and not rospy.is_shutdown(): r.sleep() self.mutex = True props = self.roboclaw_mapping["drive_left_front"] vel_cmd = self.velocity2qpps(cmd.left_front_vel, props["ticks_per_rev"], props["gear_ratio"]) self.send_velocity_cmd(props["address"], props["channel"], vel_cmd) props = self.roboclaw_mapping["drive_left_middle"] vel_cmd = self.velocity2qpps(cmd.left_middle_vel, props["ticks_per_rev"], props["gear_ratio"]) self.send_velocity_cmd(props["address"], props["channel"], vel_cmd) props = self.roboclaw_mapping["drive_left_back"] vel_cmd = self.velocity2qpps(cmd.left_back_vel, props["ticks_per_rev"], props["gear_ratio"]) self.send_velocity_cmd(props["address"], props["channel"], vel_cmd) props = self.roboclaw_mapping["drive_right_back"] vel_cmd = self.velocity2qpps(cmd.right_back_vel, props["ticks_per_rev"], props["gear_ratio"]) self.send_velocity_cmd(props["address"], props["channel"], vel_cmd) props = self.roboclaw_mapping["drive_right_middle"] vel_cmd = self.velocity2qpps(cmd.right_middle_vel, props["ticks_per_rev"], props["gear_ratio"]) self.send_velocity_cmd(props["address"], props["channel"], vel_cmd) props = self.roboclaw_mapping["drive_right_front"] vel_cmd = self.velocity2qpps(cmd.right_front_vel, props["ticks_per_rev"], props["gear_ratio"]) self.send_velocity_cmd(props["address"], props["channel"], vel_cmd) self.mutex = False def send_position_cmd(self, address, channel, target_tick): """ Wrapper around one of the send position commands :param address: :param channel: :param target_tick: int """ cmd_args = [self.corner_accel, self.corner_max_vel, self.corner_accel, target_tick, 1] if channel == "M1": return self.rc.SpeedAccelDeccelPositionM1(address, *cmd_args) elif channel == "M2": return self.rc.SpeedAccelDeccelPositionM2(address, *cmd_args) else: raise AttributeError("Received unknown channel '{}'. Expected M1 or M2".format(channel)) def read_encoder_position(self, address, channel): """Wrapper around self.rc.ReadEncM1 and self.rcReadEncM2 to simplify code""" if channel == "M1": val = self.rc.ReadEncM1(address) elif channel == "M2": val = self.rc.ReadEncM2(address) else: raise AttributeError("Received unknown channel '{}'. Expected M1 or M2".format(channel)) assert val[0] == 1 return val[1] def read_encoder_limits(self, address, channel): """Wrapper around self.rc.ReadPositionPID and returns subset of the data :return: (enc_min, enc_max) """ if channel == "M1": result = self.rc.ReadM1PositionPID(address) elif channel == "M2": result = self.rc.ReadM2PositionPID(address) else: raise AttributeError("Received unknown channel '{}'. Expected M1 or M2".format(channel)) assert result[0] == 1 return (result[-2], result[-1]) def send_velocity_cmd(self, address, channel, target_qpps): """ Wrapper around one of the send velocity commands :param address: :param channel: :param target_qpps: int """ # clip values target_qpps = max(-self.roboclaw_overflow, min(self.roboclaw_overflow, target_qpps)) accel = self.accel_pos if target_qpps < 0: accel = self.accel_neg if channel == "M1": return self.rc.DutyAccelM1(address, accel, target_qpps) elif channel == "M2": return self.rc.DutyAccelM2(address, accel, target_qpps) else: raise AttributeError("Received unknown channel '{}'. Expected M1 or M2".format(channel)) def read_encoder_velocity(self, address, channel): """Wrapper around self.rc.ReadSpeedM1 and self.rcReadSpeedM2 to simplify code""" if channel == "M1": val = self.rc.ReadSpeedM1(address) elif channel == "M2": val = self.rc.ReadSpeedM2(address) else: raise AttributeError("Received unknown channel '{}'. Expected M1 or M2".format(channel)) assert val[0] == 1 return val[1] def read_encoder_current(self, address, channel): """Wrapper around self.rc.ReadCurrents to simplify code""" if channel == "M1": return self.rc.ReadCurrents(address)[0] elif channel == "M2": return self.rc.ReadCurrents(address)[1] else: raise AttributeError("Received unknown channel '{}'. Expected M1 or M2".format(channel)) def tick2position(self, tick, enc_min, enc_max, ticks_per_rev, gear_ratio): """ Convert the absolute position from ticks to radian relative to the middle position :param tick: :param enc_min: :param enc_max: :param ticks_per_rev: :return: """ ticks_per_rad = ticks_per_rev / (2 * math.pi) if enc_min is None or enc_max is None: return tick / ticks_per_rad mid = enc_min + (enc_max - enc_min) / 2 # positive values correspond to the wheel turning left (z-axis points up) return -(tick - mid) / ticks_per_rad * gear_ratio def position2tick(self, position, enc_min, enc_max, ticks_per_rev, gear_ratio): """ Convert the absolute position from radian relative to the middle position to ticks Clip values that are outside the range [enc_min, enc_max] :param position: :param enc_min: :param enc_max: :param ticks_per_rev: :return: """ # positive values correspond to the wheel turning left (z-axis points up) position *= -1 ticks_per_rad = ticks_per_rev / (2 * math.pi) if enc_min is None or enc_max is None: return position * ticks_per_rad mid = enc_min + (enc_max - enc_min) / 2 tick = int(mid + position * ticks_per_rad / gear_ratio) return max(enc_min, min(enc_max, tick)) def qpps2velocity(self, qpps, ticks_per_rev, gear_ratio): """ Convert the given quadrature pulses per second to radian/s :param qpps: int :param ticks_per_rev: :param gear_ratio: :return: """ return qpps / (2 * math.pi * gear_ratio * ticks_per_rev) def velocity2qpps(self, velocity, ticks_per_rev, gear_ratio): """ Convert the given velocity to quadrature pulses per second :param velocity: rad/s :param ticks_per_rev: :param gear_ratio: :return: int """ return int(velocity * 2 * math.pi * gear_ratio * ticks_per_rev) def getBattery(self): return self.rc.ReadMainBatteryVoltage(self.address[0])[1] def getTemp(self): temp = [None] * 5 for i in range(5): temp[i] = self.rc.ReadTemp(self.address[i])[1] return temp def getCurrents(self): currents = [None] * 10 for i in range(5): currs = self.rc.ReadCurrents(self.address[i]) currents[2*i] = currs[1] currents[(2*i) + 1] = currs[2] return currents def getErrors(self): return self.err def killMotors(self): """Stops all motors on Rover""" for i in range(5): self.rc.ForwardM1(self.address[i], 0) self.rc.ForwardM2(self.address[i], 0) def errorCheck(self): """Checks error status of each motor controller, returns 0 if any errors occur""" for i in range(len(self.address)): self.err[i] = self.rc.ReadError(self.address[i])[1] for error in self.err: if error: self.killMotors() rospy.logerr("Motor controller Error: \n'{}'".format(error))
class RoboclawWrapper(object): """Interface between the roboclaw motor drivers and the higher level rover code""" def __init__(self): rospy.loginfo("Initializing motor controllers") # initialize attributes self.rc = None self.err = [None] * 5 self.address = [] self.current_enc_vals = None self.corner_cmd_buffer = None self.drive_cmd_buffer = None self.roboclaw_mapping = rospy.get_param('~roboclaw_mapping') self.encoder_limits = {} self.establish_roboclaw_connections() self.stop_motors() # don't move at start self.setup_encoders() # save settings to non-volatile (permanent) memory for address in self.address: self.rc.WriteNVM(address) for address in self.address: self.rc.ReadNVM(address) self.corner_max_vel = 1000 # corner motor acceleration # Even though the actual method takes longs (2*32-1), roboclaw blog says 2**15 is 100% accel_max = 2**15 - 1 accel_rate = rospy.get_param('/corner_acceleration_factor', 0.8) self.corner_accel = int(accel_max * accel_rate) self.roboclaw_overflow = 2**15 - 1 # drive motor acceleration accel_max = 2**15 - 1 accel_rate = rospy.get_param('/drive_acceleration_factor', 0.5) self.drive_accel = int(accel_max * accel_rate) self.velocity_timeout = rospy.Duration( rospy.get_param('/velocity_timeout', 2.0)) self.time_last_cmd = rospy.Time.now() self.stop_motors() # set up publishers and subscribers self.corner_cmd_sub = rospy.Subscriber("/cmd_corner", CommandCorner, self.corner_cmd_cb, queue_size=1) self.drive_cmd_sub = rospy.Subscriber("/cmd_drive", CommandDrive, self.drive_cmd_cb, queue_size=1) self.enc_pub = rospy.Publisher("/encoder", JointState, queue_size=1) self.status_pub = rospy.Publisher("/status", Status, queue_size=1) def run(self): """Blocking loop which runs after initialization has completed""" rate = rospy.Rate(8) status = Status() counter = 0 while not rospy.is_shutdown(): # Check to see if there are commands in the buffer to send to the motor controller if self.drive_cmd_buffer: drive_fcn = self.send_drive_buffer_velocity drive_fcn(self.drive_cmd_buffer) self.drive_cmd_buffer = None if self.corner_cmd_buffer: self.send_corner_buffer(self.corner_cmd_buffer) self.corner_cmd_buffer = None # read from roboclaws and publish try: self.read_encoder_values() self.enc_pub.publish(self.current_enc_vals) except AssertionError as read_exc: rospy.logwarn("Failed to read encoder values") # Downsample the rate of less important data if (counter >= 5): status.battery = self.read_battery() status.temp = self.read_temperatures() status.current = self.read_currents() status.error_status = self.read_errors() counter = 0 # stop the motors if we haven't received a command in a while now = rospy.Time.now() if now - self.time_last_cmd > self.velocity_timeout: # rather than a hard stop, send a ramped velocity command self.drive_cmd_buffer = CommandDrive() self.send_drive_buffer_velocity(self.drive_cmd_buffer) self.time_last_cmd = now # so this doesn't get called all the time self.status_pub.publish(status) counter += 1 rate.sleep() def establish_roboclaw_connections(self): """ Attempt connecting to the roboclaws :raises Exception: when connection to one or more of the roboclaws is unsuccessful """ self.rc = Roboclaw( rospy.get_param('/motor_controller/device', "/dev/serial0"), rospy.get_param('/motor_controller/baud_rate', 115200)) self.rc.Open() address_raw = rospy.get_param('motor_controller/addresses') address_list = (address_raw.split(',')) self.address = [None] * len(address_list) for i in range(len(address_list)): self.address[i] = int(address_list[i]) # initialize connection status to successful all_connected = True for address in self.address: rospy.logdebug( "Attempting to talk to motor controller ''".format(address)) version_response = self.rc.ReadVersion(address) connected = bool(version_response[0]) if not connected: rospy.logerr( "Unable to connect to roboclaw at '{}'".format(address)) all_connected = False else: rospy.logdebug( "Roboclaw version for address '{}': '{}'".format( address, version_response[1])) if all_connected: rospy.loginfo( "Sucessfully connected to RoboClaw motor controllers") else: raise Exception( "Unable to establish connection to one or more of the Roboclaw motor controllers" ) def setup_encoders(self): """Set up the encoders""" for motor_name, properties in self.roboclaw_mapping.iteritems(): if "corner" in motor_name: enc_min, enc_max = self.read_encoder_limits( properties["address"], properties["channel"]) self.encoder_limits[motor_name] = (enc_min, enc_max) else: self.encoder_limits[motor_name] = (None, None) self.rc.ResetEncoders(properties["address"]) def read_encoder_values(self): """Query roboclaws and update current motors status in encoder ticks""" enc_msg = JointState() enc_msg.header.stamp = rospy.Time.now() for motor_name, properties in self.roboclaw_mapping.iteritems(): enc_msg.name.append(motor_name) position = self.read_encoder_position(properties["address"], properties["channel"]) velocity = self.read_encoder_velocity(properties["address"], properties["channel"]) current = self.read_encoder_current(properties["address"], properties["channel"]) enc_msg.position.append( self.tick2position(position, self.encoder_limits[motor_name][0], self.encoder_limits[motor_name][1], properties['ticks_per_rev'], properties['gear_ratio'])) enc_msg.velocity.append( self.qpps2velocity(velocity, properties['ticks_per_rev'], properties['gear_ratio'])) enc_msg.effort.append(current) self.current_enc_vals = enc_msg def corner_cmd_cb(self, cmd): """ Takes the corner command and stores it in the buffer to be sent on the next iteration of the run() loop. """ rospy.logdebug("Corner command callback received: {}".format(cmd)) self.time_last_cmd = rospy.Time.now() self.corner_cmd_buffer = cmd def send_corner_buffer(self, cmd): """ Sends the corner command to the motor controller. """ # convert position to tick encmin, encmax = self.encoder_limits["corner_left_front"] left_front_tick = self.position2tick( cmd.left_front_pos, encmin, encmax, self.roboclaw_mapping["corner_left_front"]["ticks_per_rev"], self.roboclaw_mapping["corner_left_front"]["gear_ratio"]) encmin, encmax = self.encoder_limits["corner_left_back"] left_back_tick = self.position2tick( cmd.left_back_pos, encmin, encmax, self.roboclaw_mapping["corner_left_back"]["ticks_per_rev"], self.roboclaw_mapping["corner_left_back"]["gear_ratio"]) encmin, encmax = self.encoder_limits["corner_right_back"] right_back_tick = self.position2tick( cmd.right_back_pos, encmin, encmax, self.roboclaw_mapping["corner_right_back"]["ticks_per_rev"], self.roboclaw_mapping["corner_right_back"]["gear_ratio"]) encmin, encmax = self.encoder_limits["corner_right_front"] right_front_tick = self.position2tick( cmd.right_front_pos, encmin, encmax, self.roboclaw_mapping["corner_right_front"]["ticks_per_rev"], self.roboclaw_mapping["corner_right_front"]["gear_ratio"]) self.send_position_cmd( self.roboclaw_mapping["corner_left_front"]["address"], self.roboclaw_mapping["corner_left_front"]["channel"], left_front_tick) self.send_position_cmd( self.roboclaw_mapping["corner_left_back"]["address"], self.roboclaw_mapping["corner_left_back"]["channel"], left_back_tick) self.send_position_cmd( self.roboclaw_mapping["corner_right_back"]["address"], self.roboclaw_mapping["corner_right_back"]["channel"], right_back_tick) self.send_position_cmd( self.roboclaw_mapping["corner_right_front"]["address"], self.roboclaw_mapping["corner_right_front"]["channel"], right_front_tick) def drive_cmd_cb(self, cmd): """ Takes the drive command and stores it in the buffer to be sent on the next iteration of the run() loop. """ rospy.logdebug("Drive command callback received: {}".format(cmd)) self.drive_cmd_buffer = cmd self.time_last_cmd = rospy.Time.now() def send_drive_buffer_velocity(self, cmd): """ Sends the drive command to the motor controller, closed loop velocity commands """ props = self.roboclaw_mapping["drive_left_front"] vel_cmd = self.velocity2qpps(cmd.left_front_vel, props["ticks_per_rev"], props["gear_ratio"]) self.send_velocity_cmd(props["address"], props["channel"], vel_cmd) props = self.roboclaw_mapping["drive_left_middle"] vel_cmd = self.velocity2qpps(cmd.left_middle_vel, props["ticks_per_rev"], props["gear_ratio"]) self.send_velocity_cmd(props["address"], props["channel"], vel_cmd) props = self.roboclaw_mapping["drive_left_back"] vel_cmd = self.velocity2qpps(cmd.left_back_vel, props["ticks_per_rev"], props["gear_ratio"]) self.send_velocity_cmd(props["address"], props["channel"], vel_cmd) props = self.roboclaw_mapping["drive_right_back"] vel_cmd = self.velocity2qpps(cmd.right_back_vel, props["ticks_per_rev"], props["gear_ratio"]) self.send_velocity_cmd(props["address"], props["channel"], vel_cmd) props = self.roboclaw_mapping["drive_right_middle"] vel_cmd = self.velocity2qpps(cmd.right_middle_vel, props["ticks_per_rev"], props["gear_ratio"]) self.send_velocity_cmd(props["address"], props["channel"], vel_cmd) props = self.roboclaw_mapping["drive_right_front"] vel_cmd = self.velocity2qpps(cmd.right_front_vel, props["ticks_per_rev"], props["gear_ratio"]) self.send_velocity_cmd(props["address"], props["channel"], vel_cmd) def send_position_cmd(self, address, channel, target_tick): """ Wrapper around one of the send position commands :param address: :param channel: :param target_tick: int """ cmd_args = [ self.corner_accel, self.corner_max_vel, self.corner_accel, target_tick, 1 ] if channel == "M1": return self.rc.SpeedAccelDeccelPositionM1(address, *cmd_args) elif channel == "M2": return self.rc.SpeedAccelDeccelPositionM2(address, *cmd_args) else: raise AttributeError( "Received unknown channel '{}'. Expected M1 or M2".format( channel)) def read_encoder_position(self, address, channel): """Wrapper around self.rc.ReadEncM1 and self.rcReadEncM2 to simplify code""" if channel == "M1": val = self.rc.ReadEncM1(address) elif channel == "M2": val = self.rc.ReadEncM2(address) else: raise AttributeError( "Received unknown channel '{}'. Expected M1 or M2".format( channel)) assert val[0] == 1 return val[1] def read_encoder_limits(self, address, channel): """Wrapper around self.rc.ReadPositionPID and returns subset of the data :return: (enc_min, enc_max) """ if channel == "M1": result = self.rc.ReadM1PositionPID(address) elif channel == "M2": result = self.rc.ReadM2PositionPID(address) else: raise AttributeError( "Received unknown channel '{}'. Expected M1 or M2".format( channel)) assert result[0] == 1 return (result[-2], result[-1]) def send_velocity_cmd(self, address, channel, target_qpps): """ Wrapper around one of the send velocity commands :param address: :param channel: :param target_qpps: int """ # clip values target_qpps = max(-self.roboclaw_overflow, min(self.roboclaw_overflow, target_qpps)) if channel == "M1": return self.rc.SpeedAccelM1(address, self.drive_accel, target_qpps) elif channel == "M2": return self.rc.SpeedAccelM2(address, self.drive_accel, target_qpps) else: raise AttributeError( "Received unknown channel '{}'. Expected M1 or M2".format( channel)) def read_encoder_velocity(self, address, channel): """Wrapper around self.rc.ReadSpeedM1 and self.rcReadSpeedM2 to simplify code""" if channel == "M1": val = self.rc.ReadSpeedM1(address) elif channel == "M2": val = self.rc.ReadSpeedM2(address) else: raise AttributeError( "Received unknown channel '{}'. Expected M1 or M2".format( channel)) assert val[0] == 1 return val[1] def read_encoder_current(self, address, channel): """Wrapper around self.rc.ReadCurrents to simplify code""" if channel == "M1": return self.rc.ReadCurrents(address)[0] elif channel == "M2": return self.rc.ReadCurrents(address)[1] else: raise AttributeError( "Received unknown channel '{}'. Expected M1 or M2".format( channel)) def tick2position(self, tick, enc_min, enc_max, ticks_per_rev, gear_ratio): """ Convert the absolute position from ticks to radian relative to the middle position :param tick: :param enc_min: :param enc_max: :param ticks_per_rev: :return: """ ticks_per_rad = ticks_per_rev / (2 * math.pi) if enc_min is None or enc_max is None: return tick / ticks_per_rad mid = enc_min + (enc_max - enc_min) / 2 return (tick - mid) / ticks_per_rad * gear_ratio def position2tick(self, position, enc_min, enc_max, ticks_per_rev, gear_ratio): """ Convert the absolute position from radian relative to the middle position to ticks Clip values that are outside the range [enc_min, enc_max] :param position: :param enc_min: :param enc_max: :param ticks_per_rev: :return: """ ticks_per_rad = ticks_per_rev / (2 * math.pi) if enc_min is None or enc_max is None: return position * ticks_per_rad mid = enc_min + (enc_max - enc_min) / 2 tick = int(mid + position * ticks_per_rad / gear_ratio) return max(enc_min, min(enc_max, tick)) def qpps2velocity(self, qpps, ticks_per_rev, gear_ratio): """ Convert the given quadrature pulses per second to radian/s :param qpps: int :param ticks_per_rev: :param gear_ratio: :return: """ return qpps * 2 * math.pi / (gear_ratio * ticks_per_rev) def velocity2qpps(self, velocity, ticks_per_rev, gear_ratio): """ Convert the given velocity to quadrature pulses per second :param velocity: rad/s :param ticks_per_rev: :param gear_ratio: :return: int """ return int(velocity * gear_ratio * ticks_per_rev / (2 * math.pi)) def read_battery(self): """Read battery voltage from one of the roboclaws as a proxy for all roboclaws""" # roboclaw reports value in 10ths of a Volt return self.rc.ReadMainBatteryVoltage(self.address[0])[1] / 10.0 def read_temperatures(self): temp = [None] * 5 for i in range(5): # reported by roboclaw in 10ths of a Celsius temp[i] = self.rc.ReadTemp(self.address[i])[1] / 10.0 return temp def read_currents(self): currents = [None] * 10 for i in range(5): currs = self.rc.ReadCurrents(self.address[i]) # reported by roboclaw in 10ths of an Ampere currents[2 * i] = currs[1] / 100.0 currents[(2 * i) + 1] = currs[2] / 100.0 return currents def stop_motors(self): """Stops all motors on Rover""" for i in range(5): self.rc.ForwardM1(self.address[i], 0) self.rc.ForwardM2(self.address[i], 0) def read_errors(self): """Checks error status of each motor controller, returns 0 if no errors reported""" err = [0] * 5 for i in range(len(self.address)): err[i] = self.rc.ReadError(self.address[i])[1] if err[i] != 0: rospy.logerr( "Motor controller '{}' reported error code {}".format( self.address[i], err[i])) return err
resp0 = (ser0.read(10)) resp0 = resp0[:8] fltCo20 = float(resp0[2:]) ser1.write(b'Z\r\n') resp1 = ser1.read(10) resp1 = resp1[:8] fltCo21 = float(resp1[2:]) ser2.write(b'Z\r\n') resp2 = ser2.read(10) resp2 = resp2[:8] fltCo22 = float(resp2[2:]) ser3.write(b'Z\r\n') resp3 = ser3.read(10) resp3 = resp3[:8] fltCo23 = float(resp3[2:]) enc1 = rc.ReadEncM1(address) #Encoder Lines enc2 = rc.ReadEncM2(address) speed1 = rc.ReadSpeedM1(address) speed2 = rc.ReadSpeedM2(address) print format(enc2[2],'02x') print format(enc1[2],'02x') print('Heading={0:0.2F} Roll={1:0.2F} Pitch={2:0.2F}'.format(heading, roll, pitch)) print('accelX={0:0.2F} accelY={1:0.2F} accelZ={2:0.2F}'.format(accelX, accelY, accelZ)) print 'CO2 PPM =', fltCo20 *10 print 'CO2 PPM 2 =', fltCo21 *10 # multiplierZ print 'CO2 PPM 3 =', fltCo22 *10 # multiplierZ print 'CO2 PPM 4 =', fltCo23 *10 # multiplierZ time.sleep(.1) heading, roll, pitch = bno.read_euler() rc.ForwardMixed(address, 0)
vy = 0.0 vth = 0.0 current_time = rospy.Time.now() last_time = rospy.Time.now() r = rospy.Rate(1) # Init RoboClaw address = 0x80 roboclaw = Roboclaw("/dev/ttyACM0", 38400) roboclaw.Open() roboclaw.ResetEncoders(address) # _, old_encoder_1, _ = roboclaw.ReadEncM1(address) _, old_encoder_2, _ = roboclaw.ReadEncM2(address) while not rospy.is_shutdown(): current_time = rospy.Time.now() # TODO experiment with roboclaw native speed calcualtion # Going to do manual for now for consistancy. _, encoder_1, _ = roboclaw.ReadEncM1(address) _, encoder_2, _ = roboclaw.ReadEncM2(address) dt = (current_time - last_time).to_sec() V_left = ((encoder_1 - old_encoder_1)/dt) * meters_per_tick V_right = ((encoder_2 - old_encoder_2)/dt) * meters_per_tick
class MotorControllers(object): ''' Motor class contains the methods necessary to send commands to the motor controllers for the corner and drive motors. There are many other ways of commanding the motors from the RoboClaw, we suggest trying to write your own Closed loop feedback method for the drive motors! ''' def __init__(self): ## MAKE SURE TO FIX CONFIG.JSON WHEN PORTED TO THE ROVER! #self.rc = Roboclaw( config['CONTROLLER_CONFIG']['device'], # config['CONTROLLER_CONFIG']['baud_rate'] # ) rospy.loginfo("Initializing motor controllers") #self.rc = Roboclaw( rospy.get_param('motor_controller_device', "/dev/serial0"), # rospy.get_param('baud_rate', 115200)) sdev = "/dev/ttyAMA0" sdev = "/dev/serial0" self.rc = Roboclaw(sdev, 115200) self.rc.Open() self.accel = [0] * 10 self.qpps = [None] * 10 self.err = [None] * 5 # PSW address_raw = "128,129,130,131,132" #address_raw = rospy.get_param('motor_controller_addresses') address_list = (address_raw.split(',')) self.address = [None] * len(address_list) for i in range(len(address_list)): self.address[i] = int(address_list[i]) version = 1 for address in self.address: print("Attempting to talk to motor controller", address) version = version & self.rc.ReadVersion(address)[0] print version if version != 0: print "[Motor__init__] Sucessfully connected to RoboClaw motor controllers" else: raise Exception( "Unable to establish connection to Roboclaw motor controllers") self.killMotors() self.enc_min = [] self.enc_max = [] for address in self.address: #self.rc.SetMainVoltages(address, rospy.get_param('battery_low', 11)*10), rospy.get_param('battery_high', 18)*10)) if address == 131 or address == 132: #self.rc.SetM1MaxCurrent(address, int(config['MOTOR_CONFIG']['max_corner_current']*100)) #self.rc.SetM2MaxCurrent(address, int(config['MOTOR_CONFIG']['max_corner_current']*100)) self.enc_min.append(self.rc.ReadM1PositionPID(address)[-2]) self.enc_min.append(self.rc.ReadM2PositionPID(address)[-2]) self.enc_max.append(self.rc.ReadM1PositionPID(address)[-1]) self.enc_max.append(self.rc.ReadM2PositionPID(address)[-1]) else: #self.rc.SetM1MaxCurrent(address, int(config['MOTOR_CONFIG']['max_drive_current']*100)) #self.rc.SetM2MaxCurrent(address, int(config['MOTOR_CONFIG']['max_drive_current']*100)) self.rc.ResetEncoders(address) rospy.set_param('enc_min', str(self.enc_min)[1:-1]) rospy.set_param('enc_max', str(self.enc_max)[1:-1]) for address in self.address: self.rc.WriteNVM(address) for address in self.address: self.rc.ReadNVM(address) #''' voltage = self.rc.ReadMainBatteryVoltage(0x80)[1] / 10.0 lvolts = rospy.get_param('low_voltage', 11) lvolts = rospy.get_param('low_voltage', 9) if voltage >= lvolts: print "[Motor__init__] Voltage is safe at: ", print voltage, print "V" else: print "[Motor__init__] Voltage is unsafe at: ", voltage, "V ( low = ", lvolts, ")" raise Exception("Unsafe Voltage of" + voltage + " Volts") #''' i = 0 for address in self.address: self.qpps[i] = self.rc.ReadM1VelocityPID(address)[4] self.accel[i] = int(self.qpps[i] * 2) self.qpps[i + 1] = self.rc.ReadM2VelocityPID(address)[4] self.accel[i + 1] = int(self.qpps[i] * 2) i += 2 accel_max = 655359 accel_rate = 0.5 self.accel_pos = int((accel_max / 2) + accel_max * accel_rate) self.accel_neg = int((accel_max / 2) - accel_max * accel_rate) self.errorCheck() mids = [None] * 4 self.enc = [None] * 4 for i in range(4): mids[i] = (self.enc_max[i] + self.enc_min[i]) / 2 #self.cornerToPosition(mids) time.sleep(2) self.killMotors() def cornerToPosition(self, tick): ''' Method to send position commands to the corner motor :param list tick: A list of ticks for each of the corner motors to move to, if tick[i] is 0 it instead stops that motor from moving ''' speed, accel = 1000, 2000 #These values could potentially need tuning still for i in range(4): index = int(math.ceil((i + 1) / 2.0) + 2) if tick[i] != -1: if (i % 2): self.rc.SpeedAccelDeccelPositionM2(self.address[index], accel, speed, accel, tick[i], 1) else: self.rc.SpeedAccelDeccelPositionM1(self.address[index], accel, speed, accel, tick[i], 1) else: if not (i % 2): self.rc.ForwardM1(self.address[index], 0) else: self.rc.ForwardM2(self.address[index], 0) def sendMotorDuty(self, motorID, speed): ''' Wrapper method for an easier interface to control the drive motors, sends open-loop commands to the motors :param int motorID: number that corresponds to each physical motor :param int speed: Speed for each motor, range from 0-127 ''' #speed = speed/100.0 #speed *= 0.5 addr = self.address[int(motorID / 2)] if speed > 0: if not motorID % 2: command = self.rc.ForwardM1 else: command = self.rc.ForwardM2 else: if not motorID % 2: command = self.rc.BackwardM1 else: command = self.rc.BackwardM2 speed = abs(int(speed * 127)) return command(addr, speed) def sendSignedDutyAccel(self, motorID, speed): addr = self.address[int(motorID / 2)] if speed > 0: accel = self.accel_pos else: accel = self.accel_neg if not motorID % 2: command = self.rc.DutyAccelM1 else: command = self.rc.DutyAccelM2 speed = int(32767 * speed / 100.0) return command(addr, accel, speed) def getCornerEnc(self): enc = [] for i in range(4): index = int(math.ceil((i + 1) / 2.0) + 2) if not (i % 2): enc.append(self.rc.ReadEncM1(self.address[index])[1]) else: enc.append(self.rc.ReadEncM2(self.address[index])[1]) self.enc = enc return enc @staticmethod def tick2deg(tick, e_min, e_max): ''' Converts a tick to physical degrees :param int tick : Current encoder tick :param int e_min: The minimum encoder value based on physical stop :param int e_max: The maximum encoder value based on physical stop ''' return (tick - (e_max + e_min) / 2.0) * (90.0 / (e_max - e_min)) def getCornerEncAngle(self): if self.enc[0] == None: return -1 deg = [None] * 4 for i in range(4): deg[i] = int( self.tick2deg(self.enc[i], self.enc_min[i], self.enc_max[i])) return deg def getDriveEnc(self): enc = [None] * 6 for i in range(6): if not (i % 2): enc[i] = self.rc.ReadEncM1(self.address[int(math.ceil(i / 2))])[1] else: enc[i] = self.rc.ReadEncM2(self.address[int(math.ceil(i / 2))])[1] return enc def getBattery(self): return self.rc.ReadMainBatteryVoltage(self.address[0])[1] def getTemp(self): temp = [None] * 5 for i in range(5): temp[i] = self.rc.ReadTemp(self.address[i])[1] return temp def getCurrents(self): currents = [None] * 10 for i in range(5): currs = self.rc.ReadCurrents(self.address[i]) currents[2 * i] = currs[1] currents[(2 * i) + 1] = currs[2] return currents def getErrors(self): return self.err def killMotors(self): ''' Stops all motors on Rover ''' for i in range(5): self.rc.ForwardM1(self.address[i], 0) self.rc.ForwardM2(self.address[i], 0) def errorCheck(self): ''' Checks error status of each motor controller, returns 0 if any errors occur ''' for i in range(len(self.address)): self.err[i] = self.rc.ReadError(self.address[i])[1] for error in self.err: if error: self.killMotors() #self.writeError() rospy.loginfo("Motor controller Error", error) return 1 def writeError(self): ''' Writes the list of errors to a text file for later examination ''' f = open('errorLog.txt', 'a') errors = ','.join(str(e) for e in self.err) f.write('\n' + 'Errors: ' + '[' + errors + ']' + ' at: ' + str(datetime.datetime.now())) f.close()
class SerialDriver(object): ''' Class for serial UART interface to the RoboClaw Motor Controllers ''' def __init__(self): rospy.loginfo("Initilizing the motor controllers..") self.e_stop = 1 self.reg_enabled = 0 self.temp = 0 self.error = 0 self.voltage = 0 self.currents = [0,0] self._thread_lock = False self.prev_enc_ts = None self.prev_tick = [None, None] self.start_time = datetime.now() self.left_currents = [] self.right_currents = [] self.max_left_integrator = 0 self.max_right_integrator = 0 self.left_integrator = 0 self.right_integrator = 0 self.motor_lockout = 0 self._cmd_buf_flag = 0 self._l_vel_cmd_buf = 0 self._r_vel_cmd_buf = 0 self.battery_percent = 0 self.shutdown_warning = False self.shutdown_flag = False self.rate = rospy.get_param("/puffer/rate") self.delta_t = 2.0/self.rate self.rc = Roboclaw( rospy.get_param("/motor_controllers/serial_device_name"), rospy.get_param("/motor_controllers/baud_rate") ) self.rc.Open() self._set_operating_params() self._get_version() self.set_estop(0) #Clears E-stop pin self.enable_12v_reg(1) #Disables 12V Regulator self.kill_motors() #Start the motors not moving #Private Methods def _get_version(self): ''' Version check for communication verification to the motor controllers returns ther version number if sucessful, and 0 if not ''' version = self.rc.ReadVersion(self.address) if version != 0: rospy.loginfo("[Motor __init__ ] Sucessfully connected to all Motor Controllers!") rospy.loginfo( version ) rospy.set_param("/motor_controllers/firmware_version",version) else: raise Exception("Unable to establish connection to Motor controllers") return version def _set_operating_params(self): ''' Sets all the operating parameters for control of PUFFER, Pinouts, and safety parameters. returns None ''' #GPIO settings for E-stop and Regulator Enable pins self.e_stop_pin = rospy.get_param("/gpio_pins/e_stop",1) self.reg_en_pin = rospy.get_param("/gpio_pins/reg_en",1) try: GPIO.setmode(GPIO.BCM) GPIO.setwarnings(False) GPIO.setup(self.e_stop_pin, GPIO.OUT) GPIO.setup(self.reg_en_pin, GPIO.OUT) except: pass #Threadlock used for serial comm to RoboClaw self.thread_timeout = rospy.get_param("/threadlock/timeout") #Motor operating parameters self.wheel_d = rospy.get_param("/wheels/diameter") self.enc_cpr = rospy.get_param("/wheels/encoder/cts_per_rev") factor = rospy.get_param("/wheels/encoder/factor") stage_1 = rospy.get_param("/wheels/gearbox/stage1") stage_2 = rospy.get_param("/wheels/gearbox/stage2") stage_3 = rospy.get_param("/wheels/gearbox/stage3") self.accel_const = rospy.get_param("/puffer/accel_const") self.max_vel_per_s = rospy.get_param("/puffer/max_vel_per_s") self.tick_per_rev = int(self.enc_cpr * factor * stage_1 * stage_2 * stage_3) rospy.loginfo(self.tick_per_rev) rospy.set_param("tick_per_rev", self.tick_per_rev) self.max_cts_per_s = int((self.max_vel_per_s * self.tick_per_rev)/(math.pi * self.wheel_d)) self.max_accel = int(self.max_cts_per_s * self.accel_const) rospy.set_param("max_cts_per_s", self.max_cts_per_s) rospy.set_param("max_accel", self.max_accel) self.address = rospy.get_param("/motor_controllers/address", 0x80) self.rc.SetMainVoltages(self.address,int(rospy.get_param("/motor_controllers/battery/main/low", 12.0) * 10),int(rospy.get_param("motor_controllers/battery/main/high", 18.0 ) * 10)) self.rc.SetLogicVoltages(self.address,int(rospy.get_param("/motor_controllers/battery/logic/low") * 10),int(rospy.get_param("motor_controllers/battery/logic/high") * 10)) self.max_current = rospy.get_param("/motor_controllers/current/max_amps") self.motor_lockout_time = rospy.get_param("/puffer/motor_lockout_time") m1p = rospy.get_param("/motor_controllers/m1/p") m1i = rospy.get_param("/motor_controllers/m1/i") m1d = rospy.get_param("/motor_controllers/m1/d") m1qpps = rospy.get_param("/motor_controllers/m1/qpps") m2p = rospy.get_param("/motor_controllers/m2/p") m2i = rospy.get_param("/motor_controllers/m2/i") m2d = rospy.get_param("/motor_controllers/m2/d") m2qpps = rospy.get_param("/motor_controllers/m2/qpps") self.battery_max_time = rospy.get_param("/battery/max_time") self.battery_max_volts = rospy.get_param("/battery/max_volts") self.battery_coef_a = rospy.get_param("/battery/a") self.battery_coef_b = rospy.get_param("/battery/b") self.battery_coef_c = rospy.get_param("/battery/c") self.battery_warning = rospy.get_param("/battery/warning_percent") self.battery_shutdown = rospy.get_param("/battery/shutdown_percent") self.rc.SetM1VelocityPID(self.address,m1p, m1i, m1d, m1qpps) self.rc.SetM2VelocityPID(self.address,m2p, m2i, m2d, m2qpps) self.rc.WriteNVM(self.address) time.sleep(0.001) self.rc.ReadNVM(self.address) def _lock_thread(self,lock): ''' Checks the thread lock and then grabs it when it frees up no return value ''' if (lock): start = time.time() while self._thread_lock: #rospy.loginfo("in threadlock") if time.time() - start > self.thread_timeout: raise Exception("Thread lock timeout") time.sleep(0.001) self._thread_lock = True else: self._thread_lock = False def _get_Temp(self): ''' Gets the temperature of the motor controllers return: list [2] (int): Temperature values * 10 degrees C ''' self._lock_thread(1) self.temp = self.rc.ReadTemp(self.address)[1] self._lock_thread(0) self.temp = int(self.temp*100)/1000.0 return self.temp def _get_Voltage(self): ''' Gets the voltage of the motor controllers return: voltage (int) : Voltage values * 10 volts ''' self._lock_thread(1) v = self.rc.ReadMainBatteryVoltage(self.address)[1] v = int(v*100)/1000.0 if v != 0: self.voltage = v + 0.4 #accounts for the voltage drop in the diode self._lock_thread(0) return v def _get_Currents(self): ''' Gets the current of the motor controllers return: list [2] (int): Current values * 100 Amps ''' self._lock_thread(1) cur = self.rc.ReadCurrents(self.address) self._lock_thread(0) r_current = int(cur[1])/100.0 l_current = int(cur[2])/100.0 self.currents = [l_current,r_current] self.left_currents.insert(0, l_current) self.right_currents.insert(0, r_current) if (len(self.left_currents) > self.rate/2): del self.left_currents[-1] del self.right_currents[-1] left_power = 0 right_power = 0 for i in range(len(self.left_currents)): left_power += math.pow(self.left_currents[i],2) * self.delta_t right_power += math.pow(self.right_currents[i],2) * self.delta_t if (left_power >= math.pow(self.max_current,2) or right_power >= math.pow(self.max_current,2)): rospy.loginfo("Motor power exceeded max allowed! Disabling motors for %d seconds" %(self.motor_lockout_time)) self.motor_lockout = 1 self.set_estop(1) self.lockout_timestamp = time.time() if (self.motor_lockout and (time.time() - self.lockout_timestamp >= self.motor_lockout_time)): rospy.loginfo("Re-enabling the motors from timeout lock") self.motor_lockout = 0 self.set_estop(0) self.left_integrator = left_power self.right_integrator = right_power self.max_left_integrator = max(self.max_left_integrator, self.left_integrator) self.max_right_integrator = max(self.max_right_integrator, self.right_integrator) #print self.left_integrator, self.right_integrator return self.currents def _get_Errors(self): ''' Gets the error status of the motor controllers return: error (int): Error code for motor controller ''' self._lock_thread(1) self.error = self.rc.ReadError(self.address)[1] self._lock_thread(0) return self.error def _get_Encs(self): ''' Gets the encoder values of the motor controllers return: list [2] (int): Speed of motors in radians/s, computed at each delta T ''' self._lock_thread(1) r_enc = self.rc.ReadEncM1(self.address)[1] l_enc = self.rc.ReadEncM2(self.address)[1] dt = datetime.now() self._lock_thread(0) if self.prev_tick == [None, None]: l_vel_rad_s, r_vel_rad_s = 0,0 self.timestamp = 0 else: delta_t = ((dt-self.prev_enc_ts).microseconds)/1000000.0 self.timestamp = int(self.timestamp + (delta_t * 100000)) l_vel = (l_enc - self.prev_tick[0])/(delta_t) r_vel = (r_enc - self.prev_tick[1])/(delta_t) l_vel_rad_s = l_vel * (2 * math.pi/self.tick_per_rev) r_vel_rad_s = r_vel * (2 * math.pi/self.tick_per_rev) l_vel_rad_s = int(l_vel_rad_s * 1000)/1000.0 r_vel_rad_s = int(r_vel_rad_s * 1000)/1000.0 self.prev_enc_ts = dt self.prev_tick = [l_enc, r_enc] self.enc = [l_vel_rad_s, r_vel_rad_s] return l_vel_rad_s, r_vel_rad_s def _send_motor_cmds(self): l_vel = self._l_vel_cmd_buf r_vel = self._r_vel_cmd_buf l_vel *= (self.tick_per_rev/(2*math.pi)) r_vel *= (self.tick_per_rev/(2*math.pi)) l_vel = max(min(l_vel,self.max_cts_per_s), -self.max_cts_per_s) r_vel = max(min(r_vel,self.max_cts_per_s), -self.max_cts_per_s) if (( abs(l_vel) <= self.max_cts_per_s) and (abs(r_vel) <= self.max_cts_per_s)): if not self.motor_lockout: self._lock_thread(1) self.rc.SpeedAccelM1(self.address, self.max_accel, int(r_vel)) self.rc.SpeedAccelM2(self.address, self.max_accel, int(l_vel)) self._lock_thread(0) else: rospy.loginfo( "values not in accepted range" ) self.send_motor_cmds(0,0) # Public Methods def set_estop(self,val): ''' Sets the E-stop pin to stop Motor control movement until cleared Parameters: val (int): 0 - Clears E-stop 1 - Sets E-stop, disabling motor movement no return value ''' if (val != self.e_stop): if val: rospy.loginfo( "Enabling the E-stop") GPIO.output(self.e_stop_pin, 1) self.e_stop = 1 else: rospy.loginfo( "Clearing the E-stop") GPIO.output(self.e_stop_pin, 0) self.e_stop = 0 def battery_state_esimator(self): x = self.voltage y = math.pow(x,2) * self.battery_coef_a + self.battery_coef_b * x + self.battery_coef_c self.battery_percent = (100 * y/float(self.battery_max_time)) if (self.battery_percent <= self.battery_warning): self.shutdown_warning = True else: self.shutdown_warning = False if (self.battery_percent <= self.battery_shutdown): self.shutdown_flag = True self.set_estop(1) def update_cmd_buf(self, l_vel, r_vel): ''' Updates the command buffers and sets the flag that new command has been received Parameters: l_vel (int): [-0.833, 0.833] units of [rad/s] r_vel (int): [-0.833, 0.833] units of [rad/s] no return value ''' self._l_vel_cmd_buf = l_vel self._r_vel_cmd_buf = r_vel self._cmd_buf_flag = 1 def kill_motors(self): ''' Stops all motors on the assembly ''' self._lock_thread(1) self.rc.ForwardM1(self.address, 0) self.rc.ForwardM2(self.address, 0) self._lock_thread(0) def loop(self, counter): ''' Gets the data from the motor controllers to populate as class variables all data function classes are private because of threadlocks Downsample non-critical values to keep serial comm line free Parameters: counter (int): no return value ''' if (self._cmd_buf_flag): self._send_motor_cmds() self._cmd_buf_flag = 0 self._get_Encs() if not counter % 2: self._get_Currents() if not counter % 5: self._get_Errors() if not counter % 20: self._get_Temp() self._get_Voltage() self.battery_state_esimator() def enable_12v_reg(self, en): ''' Turns on/off the 12V regulator GPIO pin Parameters: en (int): 0: Disabled 1: Enabled ''' try: if (en != self.reg_enabled): if en: rospy.loginfo("Enabling the 12V Regulator") GPIO.output(self.reg_en_pin, 1) self.reg_enabled = 1 else: rospy.loginfo("Disabling the 12V Regulator") GPIO.output(self.reg_en_pin, 0) self.reg_enabled = 0 except: pass def cleanup(self): ''' Cleans up the motor controller node, stopping motors and killing all threads no return value ''' rospy.loginfo("Cleaning up the motor_controller node..") self._thread_lock = False self.kill_motors() self.set_estop(1) try: GPIO.cleanup() except: pass
class Rover(): ''' Rover class contains all the math and motor control algorithms to move the rover In order to call command the rover the only method necessary is the drive() method ''' def __init__(self): ''' Initialization of communication parameters for the Motor Controllers ''' self.rc = Roboclaw("/dev/ttyS0", 115200) self.rc.Open() self.address = [0x80, 0x81, 0x82, 0x83, 0x84] self.rc.ResetEncoders(self.address[0]) self.rc.ResetEncoders(self.address[1]) self.rc.ResetEncoders(self.address[2]) self.err = [None] * 5 def getCornerDeg(self): ''' Returns a list of angles [Deg] that each of the Corners are currently pointed at ''' encoders = [0] * 4 for i in range(4): index = int(math.ceil((i + 1) / 2.0) + 2) if (i % 2): enc = self.rc.ReadEncM2(self.address[index])[1] else: enc = self.rc.ReadEncM1(self.address[index])[1] encoders[i] = int(cals[i][0] * math.pow(enc, 2) + cals[i][1] * enc + cals[i][2]) return encoders @staticmethod def approxTurningRadius(enc): ''' Takes the list of current corner angles and approximates the current turning radius [inches] :param list [int] enc: List of encoder ticks for each corner motor ''' if enc[0] == None: return 250 try: if enc[0] > 0: r1 = (d1 / math.tan(math.radians(abs(enc[0])))) + d3 r2 = (d2 / math.tan(math.radians(abs(enc[1])))) + d3 r3 = (d2 / math.tan(math.radians(abs(enc[2])))) - d3 r4 = (d1 / math.tan(math.radians(abs(enc[3])))) - d3 else: r1 = -(d1 / math.tan(math.radians(abs(enc[0])))) - d3 r2 = -(d2 / math.tan(math.radians(abs(enc[1])))) - d3 r3 = -(d2 / math.tan(math.radians(abs(enc[2])))) + d3 r4 = -(d1 / math.tan(math.radians(abs(enc[3])))) + d3 radius = (r1 + r2 + r3 + r4) / 4 return radius except: return 250 @staticmethod def calTargetDeg(radius): ''' Takes a turning radius and calculates what angle [degrees] each corner should be at :param int radius: Radius drive command, ranges from -100 (turning left) to 100 (turning right) ''' #Scaled from 250 to 220 inches. For more information on these numbers look at the Software Controls.pdf if radius == 0: r = 250 elif -100 <= radius <= 100: r = 220 - abs(radius) * (250 / 100) else: r = 250 if r == 250: return [0] * 4 ang1 = int(math.degrees(math.atan(d1 / (abs(r) + d3)))) ang2 = int(math.degrees(math.atan(d2 / (abs(r) + d3)))) ang3 = int(math.degrees(math.atan(d2 / (abs(r) - d3)))) ang4 = int(math.degrees(math.atan(d1 / (abs(r) - d3)))) if radius > 0: return [ang2, -ang1, -ang4, ang3] else: return [-ang4, ang3, ang2, -ang1] @staticmethod def calVelocity(v, r): ''' Returns a list of speeds for each individual drive motor based on current turning radius :param int v: Drive speed command range from -100 to 100 :param int r: Turning radius command range from -100 to 100 ''' v = int(v) * (127 / 100) if (v == 0): return [v] * 6 if (r == 0 or r >= 250 or r <= -250): return [v] * 6 # No turning radius, all wheels same speed else: x = v / (abs(r) + d4) # Wheels can't move faster than max (127) a = math.pow(d2, 2) b = math.pow(d3, 2) c = math.pow(abs(r) + d1, 2) d = math.pow(abs(r) - d1, 2) e = abs(r) - d4 v1 = int(x * math.sqrt(b + d)) v2 = int(x * e) # Slowest wheel v3 = int(x * math.sqrt(a + d)) v4 = int(x * math.sqrt(a + c)) v5 = int(v) # Fastest wheel v6 = int(x * math.sqrt(b + c)) if (r < 0): velocity = [v1, v2, v3, v4, v5, v6] elif (r > 0): velocity = [v6, v5, v4, v3, v2, v1] return velocity def cornerPosControl(self, tar_enc): ''' Takes the target angle and gets what encoder tick that value is for position control :param list [int] tar_enc: List of target angles in degrees for each corner ''' x = [0] * 4 for i in range(4): a, b, c = cals[i][0], cals[i][1], cals[i][2] - tar_enc[i] d = b**2 - 4 * a * c if d < 0: print 'no soln' elif d == 0: x[i] = int((-b + math.sqrt(d[i])) / (2 * a)) else: x1 = (-b + math.sqrt(d)) / (2 * a) x2 = (-b - math.sqrt(d)) / (2 * a) if x1 > 0 and x2 <= 0: x[i] = int(x1) else: x[i] = int(x2) #I don't think this case can ever happen. speed, accel = 1000, 2000 #These values could potentially need tuning still for i in range(4): index = int(math.ceil((i + 1) / 2.0) + 2) if (i % 2): self.rc.SpeedAccelDeccelPositionM2(self.address[index], accel, speed, accel, x[i], 1) else: self.rc.SpeedAccelDeccelPositionM1(self.address[index], accel, speed, accel, x[i], 1) def motorDuty(self, motorID, speed): ''' Wrapper method for an easier interface to control the motors :param int motorID: number that corresponds to each physical motor :param int speed: Speed for each motor, range from 0-127 ''' addr = { 0: self.address[3], 1: self.address[3], 2: self.address[4], 3: self.address[4], 4: self.address[0], 5: self.address[0], 6: self.address[1], 7: self.address[1], 8: self.address[2], 9: self.address[2] } #drive forward if (speed >= 0): command = { 0: self.rc.ForwardM1, 1: self.rc.ForwardM2, 2: self.rc.ForwardM1, 3: self.rc.ForwardM2, 4: self.rc.ForwardM1, 5: self.rc.BackwardM2, #some are backward based on wiring diagram 6: self.rc.ForwardM1, 7: self.rc.ForwardM2, 8: self.rc.BackwardM1, 9: self.rc.ForwardM2 } #drive backward else: command = { 0: self.rc.BackwardM1, 1: self.rc.BackwardM2, 2: self.rc.BackwardM1, 3: self.rc.BackwardM2, 4: self.rc.BackwardM1, 5: self.rc.ForwardM2, 6: self.rc.BackwardM1, 7: self.rc.BackwardM2, 8: self.rc.ForwardM1, 9: self.rc.BackwardM2 } speed = abs(speed) return command[motorID](addr[motorID], speed) def errorCheck(self): ''' Checks error status of each motor controller, returns 0 if any errors occur ''' for i in range(5): self.err[i] = self.rc.ReadError(self.address[i])[1] for error in self.err: if error != 0: return 0 return 1 def writeError(self): ''' Writes the list of errors to a text file for later examination ''' f = open('errorLog.txt', 'a') errors = ','.join(str(e) for e in self.err) f.write('\n' + 'Errors: ' + '[' + errors + ']' + ' at: ' + str(datetime.datetime.now())) f.close() def drive(self, v, r): ''' Driving method for the Rover, rover will not do any commands if any motor controller throws an error :param int v: driving velocity command, % based from -100 (backward) to 100 (forward) :param int r: driving turning radius command, % based from -100 (left) to 100 (right) ''' if self.errorCheck(): current_radius = self.approxTurningRadius(self.getCornerDeg()) velocity = self.calVelocity(v, current_radius) self.cornerPosControl(self.calTargetDeg(r)) for i in range(6): self.motorDuty(i + 4, velocity[i]) else: self.writeError() raise Exception( "Fatal: Motor controller(s) reported errors. See errorLog.txt." ) def killMotors(self): ''' Stops all motors on Rover ''' for i in range(0, 10): self.motorDuty(i, 0)
class Argo: def __init__(self): print "Trying to connect to motors..." self.motor_status = 0 try: # First step: connect to Roboclaw controller self.port = "/dev/ttyACM0" self.argo = Roboclaw(self.port, 115200) self.argo.Open() self.address = 0x80 # Roboclaw address self.version = self.argo.ReadVersion( self.address ) # Test connection by getting the Roboclaw version except: print "Unable to connect to Roboclaw port: ", self.port, "\nCheck your port and setup then try again.\nExiting..." self.motor_status = 1 return # Follow through with setup if Roboclaw connected successfully print "Roboclaw detected! Version:", self.version[1] print "Setting up..." # Set up publishers and subscribers self.cmd_sub = rospy.Subscriber("/argo/wheel_speeds", Twist, self.get_wheel_speeds) self.encoder = rospy.Publisher("/argo/encoders", Encoder, queue_size=5) # Set class variables self.radius = 0.0728 # Wheel radius (m) self.distance = 0.372 # Distance between wheels (m) self.max_speed = 13000 # Global max speed (in QPPS) self.session_max = 13000 # Max speed for current session (in QPPS) self.rev_counts = 3200 # Encoder clicks per rotation self.circ = .4574 # Wheel circumference (m) self.counts_per_m = int(self.rev_counts / self.circ) # Encoder counts per meter self.conv = self.rev_counts / (2 * pi) # Wheel speed conversion factor self.Lref = 0 # Left wheel reference speed self.Rref = 0 # Right wheel reference speed self.Lprev_err = 0 # Previous error value for left wheel self.Rprev_err = 0 # Previous error value for right wheel self.Kp = .004 # Proportional gain self.Kd = .001 # Derivative gain self.Ki = .0004 # Integral gain self.LEint = 0 # Left wheel integral gain self.REint = 0 # Right wheel integral gain print "Setup complete, let's roll homie ;)\n\n" def reset_controller(self): self.LEint = 0 self.REint = 0 self.Lprev_err = 0 self.Rprev_err = 0 def pd_control(self, Lspeed, Rspeed): # Controller outputs a percent effort (0 - 100) which will be applied to the reference motor speeds feedback = self.read_encoders() M1 = feedback.speedM1 M2 = feedback.speedM2 # Calculate current speed error for both motors Lerror = Lspeed - M2 Rerror = Rspeed - M1 # Calculate derivative error Ldot = Lerror - self.Lprev_err Rdot = Rerror - self.Rprev_err # Calculate integral error self.LEint += Lerror self.REint += Rerror # Compute effort Lu = self.Kp * Lerror + self.Kd * Ldot + self.Ki * self.LEint Ru = self.Kp * Rerror + self.Kd * Rdot + self.Ki * self.REint # Saturate efforts if it is over +/-100% if Lu > 100.0: Lu = 100.0 elif Lu < -100.0: Lu = -100 if Ru > 100.0: Ru = 100.0 elif Ru < -100.0: Ru = -100.0 # Set new L and R speeds Lspeed = int((Lu / 100) * self.session_max) Rspeed = int((Ru / 100) * self.session_max) self.Rprev_err = Rerror self.Lprev_err = Lerror return (Lspeed, Rspeed) def move(self, Lspeed, Rspeed): if Lspeed == 0 and Rspeed == 0: self.argo.SpeedM1(self.address, 0) self.argo.SpeedM2(self.address, 0) return (Lspeed, Rspeed) = self.pd_control(Lspeed, Rspeed) self.argo.SpeedM1(self.address, Rspeed) self.argo.SpeedM2(self.address, Lspeed) def force_speed(self, Lspeed, Rspeed): self.argo.SpeedM1(self.address, Rspeed) self.argo.SpeedM2(self.address, Lspeed) def get_velocity(self, vx, vy, ax, ay): v = sqrt((vx * vx) + (vy * vy)) # Linear velocity # if vx < 0: # v = -v w = (vy * ax - vx * ay) / ((vx * vx) + (vy * vy)) # Angular velocity return (v, w) def get_wheel_speeds(self, data): r = self.radius d = self.distance v = data.linear.x w = data.angular.z # Calculate left/right wheel speeds and round to nearest integer value Ul = (v - w * d) / r Ur = (v + w * d) / r # Convert to QPPS Rspeed = int(round(Ur * self.conv)) Lspeed = int(round(Ul * self.conv)) if Rspeed > 0: Rspeed = Rspeed + 80 elif Rspeed < 0: Rspeed = Rspeed - 20 self.move(Lspeed, Rspeed) def reset_encoders(self): self.argo.ResetEncoders(self.address) def read_encoders(self): mov = Encoder() t = rospy.Time.now() # Get encoder values from Roboclaw enc2 = self.argo.ReadEncM2(self.address) enc1 = self.argo.ReadEncM1(self.address) # Get motor speeds sp1 = self.argo.ReadSpeedM1(self.address) sp2 = self.argo.ReadSpeedM2(self.address) # Extract encoder ticks and motor speeds, and publish to /argo/encoders topic mov.stamp.secs = t.secs mov.stamp.nsecs = t.nsecs mov.encoderM1 = enc1[1] mov.encoderM2 = enc2[1] mov.speedM1 = sp1[1] mov.speedM2 = sp2[1] return mov def check_battery(self): battery = self.argo.ReadMainBatteryVoltage(self.address) return battery[1]
def main(portName): print "Inicializando motores en modo de PRUEBA" ###Connection with ROS rospy.init_node("motor_node") #Suscripcion a Topicos subSpeeds = rospy.Subscriber( "/hardware/motors/speeds", Float32MultiArray, callbackSpeeds) #Topico para obtener vel y dir de los motores #Publicacion de Topicos #pubRobPos = rospy.Publisher("mobile_base/position", Float32MultiArray,queue_size = 1) #Publica los datos de la posición actual del robot pubOdometry = rospy.Publisher("mobile_base/odometry", Odometry, queue_size=1) #Publica los datos obtenidos de los encoders y analizados para indicar la posicion actual del robot #Estableciendo parametros de ROS br = tf.TransformBroadcaster( ) #Adecuando los datos obtenidos al sistema de coordenadas del robot rate = rospy.Rate(1) #Comunicacion serial con la tarjeta roboclaw Roboclaw print "Roboclaw.-> Abriendo conexion al puerto serial designacion: \"" + str( portName) + "\"" RC = Roboclaw(portName, 38400) #Roboclaw.Open(portName, 38400) RC.Open() address = 0x80 print "Roboclaw.-> Conexion establecida en el puerto serila designacion \"" + portName + "\" a 38400 bps (Y)" print "Roboclaw.-> Limpiando lecturas de enconders previas" RC.ResetEncoders(address) #Varibles de control de la velocidad global leftSpeed global rightSpeed global newSpeedData leftSpeed = 0 #[-1:0:1] rightSpeed = 0 #[-1:0:1] newSpeedData = False #Al inciar no existe nuevos datos de movmiento speedCounter = 5 #Variables para la Odometria robotPos = Float32MultiArray() robotPos = [0, 0, 0] # [X,Y,TETHA] #Ciclo ROS #print "[VEGA]:: Probando los motores de ROTOMBOTTO" while not rospy.is_shutdown(): if newSpeedData: #Se obtuvieron nuevos datos del topico /hardware/motors/speeds newSpeedData = False speedCounter = 5 #Indicando la informacion de velocidades a la Roboclaw #Realizando trasnformacion de la informacion leftSpeed = int(leftSpeed * 127) rightSpeed = int(rightSpeed * 127) #Asignando las direcciones del motor derecho if rightSpeed >= 0: RC.ForwardM1(address, rightSpeed) else: RC.BackwardM1(address, -rightSpeed) #Asignando las direcciones del motor izquierdo if leftSpeed >= 0: RC.ForwardM2(address, leftSpeed) else: RC.BackwardM2(address, -leftSpeed) else: #NO se obtuvieron nuevos datos del topico, los motores se detienen speedCounter -= 1 if speedCounter == 0: RC.ForwardM1(address, 0) RC.ForwardM2(address, 0) if speedCounter < -1: speedCounter = -1 #------------------------------------------------------------------------------------------------------- #Obteniendo informacion de los encoders encoderLeft = RC.ReadEncM2( address) #Falta multiplicarlo por -1, tal vez no sea necesario encoderRight = RC.ReadEncM1( address ) #El valor negativo obtenido en este encoder proviene de la posicion de orientacion del motor. RC.ResetEncoders(address) #print "Lectura de los enconders Encoders: EncIzq" + str(encoderLeft) + " EncDer" + str(encoderRight) ###Calculo de la Odometria robotPos = calculateOdometry(robotPos, encoderLeft, encoderRight) #pubRobPos=.publish(robotPos) ##Publicando los datos de la pocición obtenida ts = TransformStamped() ts.header.stamp = rospy.Time.now() ts.header.frame_id = "odom" ts.child_frame_id = "base_link" ts.transform.translation.x = robotPos[0] ts.transform.translation.y = robotPos[1] ts.transform.translation.z = 0 ts.transform.rotation = tf.transformations.quaternion_from_euler( 0, 0, robotPos[2]) br.sendTransform((robotPos[0], robotPos[1], 0), ts.transform.rotation, rospy.Time.now(), ts.child_frame_id, ts.header.frame_id) msgOdom = Odometry() msgOdom.header.stamp = rospy.Time.now() msgOdom.pose.pose.position.x = robotPos[0] msgOdom.pose.pose.position.y = robotPos[1] msgOdom.pose.pose.position.z = 0 msgOdom.pose.pose.orientation.x = 0 msgOdom.pose.pose.orientation.y = 0 msgOdom.pose.pose.orientation.z = math.sin(robotPos[2] / 2) msgOdom.pose.pose.orientation.w = math.cos(robotPos[2] / 2) pubOdometry.publish(msgOdom) #Publicando los datos de odometría rate.sleep() #Fin del WHILE ROS #------------------------------------------------------------------------------------------------------ RC.ForwardM1(address, 0) RC.ForwardM2(address, 0) RC.Close()
class MotorControllersV2(object): ''' Motor class contains the methods necessary to send commands to the motor controllers for the corner and drive motors. There are many other ways of commanding the motors from the RoboClaw, we suggest trying to write your own Closed loop feedback method for the drive motors! ''' def __init__(self): ## MAKE SURE TO FIX CONFIG.JSON WHEN PORTED TO THE ROVER! #self.rc = Roboclaw( config['CONTROLLER_CONFIG']['device'], # config['CONTROLLER_CONFIG']['baud_rate'] # ) rospy.loginfo("Initializing motor controllers") #self.rc = Roboclaw( rospy.get_param('motor_controller_device', "/dev/serial0"), # rospy.get_param('baud_rate', 115200)) self.rc = Roboclaw("/dev/ttyS0", 115200) self.rc.Open() self.accel = [0] * 10 self.qpps = [None] * 10 self.err = [None] * 5 address_raw = rospy.get_param('motor_controller_addresses') address_list = (address_raw.split(',')) self.address = [None] * len(address_list) for i in range(len(address_list)): self.address[i] = int(address_list[i]) version = 1 for address in self.address: rospy.loginfo("Attempting to talk to motor controller: " + str(address)) version = version & self.rc.ReadVersion(address)[0] rospy.loginfo("Motor controller version: " + str(version)) if version != 0: rospy.loginfo( "Sucessfully connected to RoboClaw motor controllers") else: rospy.logerr( "Unable to establish connection to Roboclaw motor controllers") raise Exception( "Unable to establish connection to Roboclaw motor controllers") self.killMotors() for address in self.address: self.rc.ResetEncoders(address) for address in self.address: self.rc.WriteNVM(address) for address in self.address: self.rc.ReadNVM(address) ''' voltage = self.rc.ReadMainBatteryVoltage(0x80)[1]/10.0 if voltage >= rospy.get_param('low_voltage',11): print "[Motor__init__] Voltage is safe at: ",voltage, "V" else: raise Exception("Unsafe Voltage of" + voltage + " Volts") ''' i = 0 for address in self.address: self.qpps[i] = self.rc.ReadM1VelocityPID(address)[4] self.accel[i] = int(self.qpps[i] * 2) self.qpps[i + 1] = self.rc.ReadM2VelocityPID(address)[4] self.accel[i + 1] = int(self.qpps[i] * 2) i += 2 accel_max = 655359 accel_rate = 0.5 self.accel_pos = int((accel_max / 2) + accel_max * accel_rate) self.accel_neg = int((accel_max / 2) - accel_max * accel_rate) self.errorCheck() self.drive_enc = [None] * 10 time.sleep(2) self.killMotors() def sendMotorDuty(self, motorID, speed): ''' Wrapper method for an easier interface to control the drive motors, sends open-loop commands to the motors :param int motorID: number that corresponds to each physical motor :param int speed: Speed for each motor, range from 0-127 ''' #speed = speed/100.0 #speed *= 0.5 addr = self.address[int(motorID / 2)] if speed > 0: if not motorID % 2: command = self.rc.ForwardM1 else: command = self.rc.ForwardM2 else: if not motorID % 2: command = self.rc.BackwardM1 else: command = self.rc.BackwardM2 speed = abs(int(speed * 127)) return command(addr, speed) def sendSignedDutyAccel(self, motorID, speed): addr = self.address[int(motorID / 2)] if speed > 0: accel = self.accel_pos else: accel = self.accel_neg if not motorID % 2: command = self.rc.DutyAccelM1 else: command = self.rc.DutyAccelM2 speed = int(32767 * speed / 100.0) return command(addr, accel, speed) def getDriveEnc(self): drive_enc = [] for i in range(10): index = int(math.ceil((i + 1) / 2.0) - 1) if not (i % 2): drive_enc.append(self.rc.ReadEncM1(self.address[index])[1]) else: drive_enc.append(self.rc.ReadEncM2(self.address[index])[1]) self.drive_enc = drive_enc return drive_enc def getBattery(self): return self.rc.ReadMainBatteryVoltage(self.address[0])[1] def getTemp(self): temp = [None] * 5 for i in range(5): temp[i] = self.rc.ReadTemp(self.address[i])[1] return temp def getCurrents(self): currents = [None] * 10 for i in range(5): currs = self.rc.ReadCurrents(self.address[i]) currents[2 * i] = currs[1] currents[(2 * i) + 1] = currs[2] return currents def getErrors(self): return self.err def killMotors(self): ''' Stops all motors on Rover ''' for i in range(5): self.rc.ForwardM1(self.address[i], 0) self.rc.ForwardM2(self.address[i], 0) def errorCheck(self): ''' Checks error status of each motor controller, returns 0 if any errors occur ''' for i in range(len(self.address)): self.err[i] = self.rc.ReadError(self.address[i])[1] for error in self.err: if error: self.killMotors() #self.writeError() rospy.loginfo("Motor controller Error: " + str(error)) return 1 def writeError(self): ''' Writes the list of errors to a text file for later examination ''' f = open('errorLog.txt', 'a') errors = ','.join(str(e) for e in self.err) f.write('\n' + 'Errors: ' + '[' + errors + ']' + ' at: ' + str(datetime.datetime.now())) f.close()
import time import serial import math from roboclaw import Roboclaw rc = Roboclaw("/dev/ttyS0", 115200) i = rc.Open() print("open status = [" + str(i) + "]") enc1 = rc.ReadEncM1(0x80) enc2 = rc.ReadEncM2(0x80) enc3 = rc.ReadEncM1(0x81) enc4 = rc.ReadEncM2(0x81) enc5 = rc.ReadEncM1(0x82) enc6 = rc.ReadEncM2(0x82) rc.ForwardM1(0x80, 100) rc.ForwardM2(0x80, 100) rc.ForwardM1(0x81, 100) rc.ForwardM2(0x81, 100) rc.ForwardM1(0x82, 100) rc.ForwardM2(0x82, 100) time.sleep(5) enc1e = rc.ReadEncM1(0x80) enc2e = rc.ReadEncM2(0x80) enc3e = rc.ReadEncM1(0x81) enc4e = rc.ReadEncM2(0x81) enc5e = rc.ReadEncM1(0x82) enc6e = rc.ReadEncM2(0x82) print("encs:", enc1, enc2, enc3, enc4, enc5, enc6)
# A short and sweet script to test communication with a single roboclaw motor controller. # usage # $ python roboclawtest.py 128 from time import sleep import sys from os import path # need to add the roboclaw.py file in the path sys.path.append( path.join(path.expanduser('~'), 'osr_ws/src/osr-rover-code/ROS/osr/src')) from roboclaw import Roboclaw if __name__ == "__main__": address = int(sys.argv[1]) roboclaw = Roboclaw("/dev/serial0", 115200) roboclaw.Open() print roboclaw.ReadVersion(address) print roboclaw.ReadEncM1(address)
class comm: def __init__(self): self.rc = Roboclaw("/dev/ttyS0", 115200) self.rc.Open() self.accel = [0] * 10 self.qpps = [None] * 10 self.err = [None] * 5 self.address = [128, 129, 130, 131, 132] ''' version = 1 for address in self.address: print("Attempting to talk to motor controller",address) version = version & self.rc.ReadVersion(0x80) print(version) if version != 0: print("[Motor__init__] Sucessfully connected to RoboClaw motor controllers") else: raise Exception("Unable to establish connection to Roboclaw motor controllers") ''' def accellDriveMotors(self, speeds): for i in range(3): self.rc.SpeedAccelM1(self.address[i], 7000, speeds[i * 2] * 32767 / 500) self.rc.SpeedAccelM2(self.address[i], 7000, speeds[(i * 2 + 1)] * 32767 / 500) def getCornerEncoders(self): enc = [] for i in range(4): index = int(math.ceil((i + 1) / 2.0) + 2) if not (i % 2): enc.append(self.rc.ReadEncM1(self.address[index])[1]) else: enc.append(self.rc.ReadEncM2(self.address[index])[1]) return enc def moveCorners(self, tick): enc = [] speed, accel = 1000, 2000 for i in range(4): index = int(math.ceil((i + 1) / 2.0) + 2) if not (i % 2): enc.append(self.rc.ReadEncM1(self.address[index])[1]) else: enc.append(self.rc.ReadEncM2(self.address[index])[1]) if (abs(tick[i] - enc[i]) < 25): tick[i] = -1 if (tick[i] != -1): if (i % 2): self.rc.SpeedAccelDeccelPositionM2(self.address[index], accel, speed, accel, tick[i], 1) else: self.rc.SpeedAccelDeccelPositionM1(self.address[index], accel, speed, accel, tick[i], 1) else: if (i % 2): self.rc.ForwardM2(self.address[index], 0) else: self.rc.ForwardM1(self.address[index], 0)
rc.SetPWMMode(0x80, 0) # Locked Antiphase #rc.ReadPWMMode(0x80) rc.SetM1EncoderMode(0x80, 0) # No RC/Analog support + Quadrature encoder #rc.ReadEncoderModes(0x80) getConfig = rc.GetConfig(0x80) config = getConfig[1] # index zero is 1 for success, 0 for failure. config = config | 0x0003 # Packet serial mode config = config | 0x8000 # Multi-Unit mode rc.SetConfig(0x80, config) rc.SetPinFunctions(0x80, 2, 0, 0) # S3 = E-Stop, S4 = Disabled, S5 = Disabled rc.WriteNVM(0x80) rc.ReadEncM1(0x80) rc.ResetEncoders(0x80) rc.ReadEncM1(0x80) p = 15000 i = 1000 d = 500 qpps = 3000 rc.SetM1VelocityPID(0x80, p, i, d, qpps) rc.ReadM1VelocityPID(0x80) rc.SpeedM1(0x80, 250) rc.ReadM1MaxCurrent(0x80) rc.ReadCurrents(0x80)