def do_POST(self): content_length = int( self.headers['Content-Length']) # <--- Gets the size of data post_data = self.rfile.read( content_length) # <--- Gets the data itself # logging.info("POST request,\nPath: %s\nHeaders:\n%s\n\nBody:\n%s\n", str(self.path), str(self.headers), # post_data.decode('utf-8')) command = post_data.decode("utf-8") if command == 'start_job': Commands.write_start_job('') elif command == 'hold_on': Commands.write_hold('1') elif command == 'hold_off': Commands.write_hold('0') elif command == 'servo_on': Commands.write_servo_power('1') elif command == 'servo_off': Commands.write_servo_power('0') elif command == 'move_s_l' or command == 'move_s_r': c_pos = get_position() Commands.write_linear_move( MoveL.MoveL( 0, SPEED, 0, (c_pos.get_x() - MOVE_MM) if command == 'move_s_l' else (c_pos.get_x() + MOVE_MM), c_pos.get_y(), c_pos.get_z(), c_pos.get_tx(), c_pos.get_ty(), c_pos.get_tz(), Utils.binary_to_decimal(0x00000001))) elif command == 'move_l_l' or command == 'move_l_r': c_pos = get_position() Commands.write_linear_move( MoveL.MoveL(0, SPEED, 0, c_pos.get_x(), (c_pos.get_y() - MOVE_MM) if command == 'move_l_l' else (c_pos.get_y() + MOVE_MM), c_pos.get_z(), c_pos.get_tx(), c_pos.get_ty(), c_pos.get_tz(), Utils.binary_to_decimal(0x00000001))) elif command == 'move_u_l' or command == 'move_u_r': c_pos = get_position() Commands.write_linear_move( MoveL.MoveL(0, SPEED, 0, c_pos.get_x(), c_pos.get_y(), (c_pos.get_z() - MOVE_MM) if command == 'move_u_l' else (c_pos.get_z() + MOVE_MM), c_pos.get_tx(), c_pos.get_ty(), c_pos.get_tz(), Utils.binary_to_decimal(0x00000001))) # Todo, do not use, ultra dangerous # Todo, implement these some day with posture speed option # elif command == 'move_r_l' or command == 'move_r_r': # c_pos = get_position() # Commands.write_linear_move(MoveL.MoveL( # 0, 1, 0, # c_pos.get_x(), c_pos.get_y(), c_pos.get_z(), # (c_pos.get_tx() - 5.00) if command == 'move_r_l' else (c_pos.get_tx() + 5.0), # c_pos.get_ty(), c_pos.get_tz(), # Utils.binary_to_decimal(0x00000001) # )) self._set_headers() self.wfile.write("".format(self.path).encode('utf-8'))
def write_io_signals(io): response = Response.Response(Socket.exec_single_command( Command.Command("IOWRITE", io.get_io_write_command())) ) Utils.print_response_details(response.get_response()) logging.info( '[i] IO write command run successfully!' if response.is_success() else '[E] IO write command run failed!') return response
def write_servo_power(command): if command not in '1' and command not in '0': logging.error('[E] servo power command can only be 1 (on) or 0 (off)') return response = Response.Response(Socket.exec_single_command(Command.Command("SVON", command))) Utils.print_response_details(response.get_response()) logging.info('[i] servo command run successfully!' if response.is_success() else '[E] servo command run failed!') return response
def read_all_job_names(): response = Response.Response(Socket.exec_single_command( Command.Command("RJDIR", "*")) # * means to read all registered jobs ) Utils.print_response_details(response.get_response()) logging.info('[i] Read job names command run successfully!' if response.is_success() else '[E] Read job names command run failed!') return response
def go(self, move_l, wait=True, poll_limit_seconds=30): """ commands robot to move into position linear way :param move_l: MoveL object describing target position and move settings :param wait: wait for move to complete or not :param poll_limit_seconds: functions as a timeout of wait is enabled :return: boolean """ self.stopped = False Commands.write_hold('0') # disable hold if currently enabled Commands.write_linear_move( move_l=move_l) # execute wanted move command current = 0 if not wait: return True for x in range(poll_limit_seconds): if self.stopped: return False time.sleep(1) cp = Commands.read_current_specified_coordinate_system_position( # returns CurrentPos object str(move_l.get_coordinate_specification()), '0') if Utils.is_in_position(move_l, cp): return True else: current = current + 1 if current == poll_limit_seconds: return False
def test_linear_motion_move(self): move_l = MoveL.MoveL( MoveL.MoveL.motion_speed_selection_posture_speed, 5, MoveL.MoveL.coordinate_specification_base_coordinate, 352.769, 202.779, 120.658, -1.34, 35.78, 27.84, Utils.binary_to_decimal(0x00000001), 0, 0, 0, 0, 0, 0, 0) res = Commands.write_linear_move(move_l=move_l) self.assertEqual(res.get_response(), '0000')
def exec_single_command(command): if nx100_remote_control.MOCK_RESPONSE: return Utils.clean_response(MockResponse.get_mock_response(command)) client = socket.socket(socket.AF_INET, socket.SOCK_STREAM) client.settimeout(5) # connect the client client.connect((nx100_remote_control.NX100_IP_ADDRESS, nx100_remote_control.NX100_TCP_PORT)) # start request start_request = "CONNECT Robot_access" + CRLF client.send(start_request.encode()) response = client.recv(4096) start_response = repr(response) if 'OK: NX Information Server' not in start_response: client.close() logging.error('[E] Command start request response not ok!') return # command request cmd_data_length = Utils.command_data_length(command) command_request = "HOSTCTRL_REQUEST " + command.name + " " + str(cmd_data_length) + CRLF logging.info('Sending command: ' + command_request) client.send(command_request.encode()) response = client.recv(4096) command_response = repr(response) if ('OK: ' + command.name) not in command_response: client.close() logging.error('[E] Command request response not ok!') return # command data request command_data_request = command.data + (CR if len(command.data) > 0 else '') client.send(command_data_request.encode()) response = client.recv(4096) command_data_response = repr(response) # close socket client.close() return Utils.clean_response(command_data_response)
def read_status(): response_data = Socket.exec_single_command(Command.Command("RSTATS", "")) Utils.print_response_details(response_data) parts = response_data.split(',') data_1 = Utils.decimal_to_binary(int(parts[0])) data_2 = Utils.decimal_to_binary(int(parts[1])) s = Status.Status(data_1, data_2) logging.info('Command remote: ' + str(s.is_command_remote()) + ', ' + 'Play: ' + str(s.is_play()) + ', ' + 'Teach ' + str(s.is_teach()) + ', ' + 'Safety speed operation: ' + str(s.is_safety_speed_operation()) + ', ' + 'Running: ' + str(s.is_running()) + ', ' + 'Auto: ' + str(s.is_auto()) + ', ' + 'One cycle: ' + str(s.is_one_cycle()) + ', ' + 'Step: ' + str(s.is_step()) + ', ' + 'Servo on: ' + str(s.is_servo_on()) + ', ' + 'Error occurring: ' + str(s.is_error_occurring()) + ', ' + 'Alarm occurring: ' + str(s.is_alarm_occurring()) + ', ' + 'Command hold: ' + str(s.is_command_hold()) + ', ' + 'External hold: ' + str(s.is_external_hold()) + ', ' + 'Programming pendant hold: ' + str(s.is_programming_pendant_hold())) return s
def test_joint_motion_move(self): move_j = MoveJ.MoveJ( 25, # speed % MoveJ.MoveJ.coordinate_specification_base_coordinate, 352.769, 202.779, 120.658, -1.34, 35.78, 27.84, Utils.binary_to_decimal(0x00000001), 0, 0, 0, 0, 0, 0, 0) res = Commands.write_joint_motion_move(move_j=move_j) self.assertEqual(res.get_response(), '0000')
def robot_in_target_point_callback(move_l, timeout=10, _callback_success=None, _callback_failed=None): current = 0 for x in range(timeout): time.sleep(1) cp = read_current_specified_coordinate_system_position( # returns CurrentPos object str(move_l.get_coordinate_specification), '0' ) if Utils.is_in_position(move_l, cp): if _callback_success: _callback_success() break else: return True else: current = current + 1 if current == timeout: if _callback_failed: _callback_failed() break else: return False
# handle joysticks left_x, left_y = controller.get_left_stick() # joystick logic handling if left_x < -0.2 or left_x > 0.2: if time.has_seconds_passed(WAIT_FOR): time.set_time_now(time.get_current_millis()) c_pos = get_position() Commands.write_linear_move( MoveL.MoveL(0, int( (abs(left_x) * 2) * SPEED), COORDINATE_SYSTEM, (c_pos.get_x() + int(left_x * 20)), c_pos.get_y(), c_pos.get_z(), c_pos.get_tx(), c_pos.get_ty(), c_pos.get_tz(), Utils.binary_to_decimal(0x00000001))) ball_pos[0] += int(left_x * 5) if left_y < -0.2 or left_y > 0.2: if time.has_seconds_passed(WAIT_FOR): time.set_time_now(time.get_current_millis()) c_pos = get_position() Commands.write_linear_move( MoveL.MoveL(0, int((abs(left_y) * 2) * SPEED), COORDINATE_SYSTEM, c_pos.get_x(), (c_pos.get_y() - int(left_y * 20)), c_pos.get_z(), c_pos.get_tx(), c_pos.get_ty(), c_pos.get_tz(), Utils.binary_to_decimal(0x00000001))) ball_pos[1] += int(left_y * 5)
def write_cancel(): response = Response.Response(Socket.exec_single_command(Command.Command("CANCEL", ""))) Utils.print_response_details(response.get_response()) logging.info('[i] cancel command run successfully!' if response.is_success() else '[E] cancel command run failed!') return response
def read_current_job_details(): response_data = Socket.exec_single_command(Command.Command("RJSEQ", "")) Utils.print_response_details(response_data) return JobDetail.JobDetail(response_data)
def read_current_specified_coordinate_system_position(coordinate_system, include_external_axis='0'): position_response = Socket.exec_single_command( Command.Command("RPOSC", (coordinate_system + ', ' + include_external_axis)) ) Utils.print_response_details(position_response) return CurrentPos.CurrentPos(position_response)
def write_master_job(job_name): response = Response.Response(Socket.exec_single_command(Command.Command("SETMJ", job_name))) Utils.print_response_details(response.get_response()) logging.info('[i] set master job command run successfully!' if response.is_success() else '[E] set master job command run failed!') return response
def read_current_joint_coordinate_position(): response_data = Socket.exec_single_command(Command.Command("RPOSJ", "")) Utils.print_response_details(response_data) return response_data