diff --git a/drivers/sub8_videoray_m5_thruster/sub8_thruster_comm/__init__.py b/drivers/sub8_videoray_m5_thruster/sub8_thruster_comm/__init__.py index e6435fdf..ef0f9ccd 100644 --- a/drivers/sub8_videoray_m5_thruster/sub8_thruster_comm/__init__.py +++ b/drivers/sub8_videoray_m5_thruster/sub8_thruster_comm/__init__.py @@ -2,12 +2,14 @@ from .thruster_fake import FakeThrusterPort -def thruster_comm_factory(port_info, fake=False): - '''Return the appropriate thruster communication class +def thruster_comm_factory(port_info, thruster_definitions, fake=False): + ''' + Return the appropriate thruster communication class Purpose: - - Use the same code to run both simulated thrusters and real thrusters + - Use the same code to run both simulated thrusters and real thrusters ''' if fake: - return FakeThrusterPort(port_info) + return FakeThrusterPort(port_info, thruster_definitions) else: - return ThrusterPort(port_info) + return ThrusterPort(port_info, thruster_definitions) + diff --git a/drivers/sub8_videoray_m5_thruster/sub8_thruster_comm/thruster_comm.py b/drivers/sub8_videoray_m5_thruster/sub8_thruster_comm/thruster_comm.py index de410ed3..eb8acce9 100644 --- a/drivers/sub8_videoray_m5_thruster/sub8_thruster_comm/thruster_comm.py +++ b/drivers/sub8_videoray_m5_thruster/sub8_thruster_comm/thruster_comm.py @@ -13,18 +13,26 @@ class ThrusterPort(object): _timeout = 0.01 # How long to wait for a serial response _max_motor_id = 100 # Max motor ID for which to verify the existence - def __init__(self, port_info): + def __init__(self, port_info, thruster_definitions): '''Communicate on a single port with some thrusters - port_info should be a dictionary, drawn from a .yaml of the form... - - - port: /dev/serial/by-id/usb-FTDI_FT232R_USB_UART_A403IMC9-if00-port0 - thrusters: - FLV: { - node_id: 10, - } - FLL: { - node_id: 11, - } + port_info an associates a serial port name with a list of thruster names. + YAML form: (part of list) + + - port: /dev/serial/by-id/usb-MIL_Data_Merge_Board_Ports_1_to_4_DMBP14-if00-port0 + thruster_names: [FLH, FLV] + + thruster_definitions should be a dictionary mapping thruster names to thruster properties. + YAML form: + + thrusters: + FLH: { + motor_id: 0 + position: [0.2678, 0.2795, 0.0], + direction: [-0.866, 0.5, 0.0], + bounds: [-90.0, 90.0] + } + + Note: - The thrusters automatically shut down if they do not recieve a command for ~2 seconds @@ -41,7 +49,8 @@ def __init__(self, port_info): ''' self.port_name = port_info['port'] self.port = self.connect_port(self.port_name) - self.thruster_dict = {} + self.thruster_dict = {} # holds the motor_ids of all the thrusters that were supposed + # to be here and were actually found # Determine which thrusters are really on this port self.motor_ids_on_port = [] @@ -52,9 +61,9 @@ def __init__(self, port_info): # Load thruster configurations and check if the requested thruster exists on this port self.missing_thrusters = [] - for thruster_name, thruster_info in port_info['thrusters'].items(): + for thruster_name in port_info['thruster_names']: try: - self.load_thruster_config(thruster_name, thruster_info) + self.load_thruster_config(thruster_name, thruster_definitions) except IOError: self.missing_thrusters.append(thruster_name) continue @@ -68,15 +77,18 @@ def connect_port(self, port_name): raise(e) return serial_port - def load_thruster_config(self, thruster_name, thruster_info): + def load_thruster_config(self, thruster_name, thruster_definitions): + '''Loads the motor_id from the config file if the thruster was found''' # Get our humungous error string ready errstr = "Could not find motor_id {} (Called {}) on port {}; existing ids are {}".format( thruster_info['node_id'], thruster_name, self.port_name, self.motor_ids_on_port) + # Check if we can actually find the thruster on this port - if not int(thruster_info['node_id']) in self.motor_ids_on_port: + motor_id = int(thruster_info[thruster_name][motor_id]) + if not motor_id in self.motor_ids_on_port: rospy.logerr(errstr) raise(IOError(errstr)) - self.thruster_dict[thruster_name] = int(thruster_info['node_id']) + self.thruster_dict[thruster_name] = motor_id def checksum_struct(self, _struct): '''Take a struct, convert it to a bytearray, and append its crc32 checksum''' @@ -124,7 +136,8 @@ def make_poll_payload(self, motor_id): return payload def to_register(self, motor_id, register, value=None): - '''Get a register (and optionally try to set it) + ''' + Get a register (and optionally try to set it) Note: This fails randomly ''' assert register in Const.csr_address.keys(), "Unknown register, {}".format(register) @@ -152,14 +165,11 @@ def to_register(self, motor_id, register, value=None): ) packet = header + payload - # prev = self.port.read(100) self.port.write(bytes(packet)) response_bytearray = self.port.read(Const.response_normal_length + return_size) if len(response_bytearray) == 0: return None - # rest = self.port.read(100) - # if len(response_bytearray) == response = struct.unpack('