xiugai yidui

This commit is contained in:
LiangShiyun 2025-06-14 00:20:57 +08:00
parent e591f09604
commit 93bff48747
294 changed files with 129 additions and 28 deletions

File diff suppressed because one or more lines are too long

Binary file not shown.

View File

@ -2209,7 +2209,7 @@ class Thermotherapy_Task(TaskBase):
self.resources.logger.log_info("Executing Thermotherapy_Task") self.resources.logger.log_info("Executing Thermotherapy_Task")
self.move_to_startpos() self.move_to_startpos()
self.resources.logger.log_info('启动热疗按摩') self.resources.logger.log_info('启动热疗按摩')
self.resources.robot.thermotherapy.set_working_status(cur_level=self.resources.gear, heat_level=self.resources.temperature, vib_level=self.resources.shake) # self.resources.robot.thermotherapy.set_working_status(cur_level=self.resources.gear, heat_level=self.resources.temperature, vib_level=self.resources.shake)
self.tasks_queue_execution() # 按照任务队列执行任务 self.tasks_queue_execution() # 按照任务队列执行任务
return "stop" return "stop"

View File

@ -198,8 +198,8 @@ class MassageRobot:
self.ion = None self.ion = None
self.force_plan = ForcePlanner() self.force_plan = ForcePlanner()
# 传感器 # 传感器
# self.force_sensor = None self.force_sensor = None
self.force_sensor = XjcSensor() # self.force_sensor = XjcSensor()
# self.force_sensor.connect() # self.force_sensor.connect()
# 控制器,初始为导纳控制 # 控制器,初始为导纳控制
self.controller_manager = ControllerManager(self.arm_state) self.controller_manager = ControllerManager(self.arm_state)
@ -422,6 +422,7 @@ class MassageRobot:
return 0 #读取成功并置零成功 return 0 #读取成功并置零成功
def sensor_enable(self): def sensor_enable(self):
print("^^^^^^^^^^^^^^^^^^^^^^^^^")
code = self.force_sensor.enable_active_transmission() code = self.force_sensor.enable_active_transmission()
max_try = 3 max_try = 3
while code!= 0 and max_try > 0: while code!= 0 and max_try > 0:
@ -439,49 +440,59 @@ class MassageRobot:
) )
# sys.exit(0) # sys.exit(0)
return -1 return -1
print("^^^^^^^^^^^^^^^^^^^^^^^^^")
return 0 return 0
def update_wrench(self): def update_wrench(self):
# 当前的机械臂到末端转换 (实时) # 当前的机械臂到末端转换 (实时)
# print("com111111")
b_rotation_s = R.from_quat(self.arm_state.arm_orientation).as_matrix() b_rotation_s = R.from_quat(self.arm_state.arm_orientation).as_matrix()
# 读取数据 # 读取数据
# print("com2222222222")
sensor_data = self.force_sensor.read() sensor_data = self.force_sensor.read()
# print("com3333")
# self.logger.log_info(f"传感器数据{sensor_data}") # self.logger.log_info(f"传感器数据{sensor_data}")
if sensor_data is None: if sensor_data is None:
self.force_sensor.stop_background_reading() self.force_sensor.stop_background_reading()
self.logger.log_error("传感器数据读取失败") self.logger.log_error("传感器数据读取失败")
return -1 return -1
# print("com44444444444444444444444444444444444444444")
# 反重力补偿 # 反重力补偿
sensor_data[:3] = sensor_data[:3] + self.force_zero + self.b_rotation_s_set0.T @ self.gravity_base sensor_data[:3] = sensor_data[:3] + self.force_zero + self.b_rotation_s_set0.T @ self.gravity_base
sensor_data[3:] = sensor_data[3:] + self.torque_zero + np.cross(self.mass_center_position, self.b_rotation_s_set0.T @ self.gravity_base) sensor_data[3:] = sensor_data[3:] + self.torque_zero + np.cross(self.mass_center_position, self.b_rotation_s_set0.T @ self.gravity_base)
# 传感器数据通过矫正计算得到外来施加力 传感器坐标系下 # 传感器数据通过矫正计算得到外来施加力 传感器坐标系下
# 重力 # 重力
# print("com5555555")
gravity_in_sensor = b_rotation_s.T @ self.gravity_base gravity_in_sensor = b_rotation_s.T @ self.gravity_base
s_force = sensor_data[:3] - self.force_zero - gravity_in_sensor s_force = sensor_data[:3] - self.force_zero - gravity_in_sensor
# 力矩 # 力矩
s_torque = sensor_data[3:] - self.torque_zero - np.cross(self.mass_center_position,gravity_in_sensor) s_torque = sensor_data[3:] - self.torque_zero - np.cross(self.mass_center_position,gravity_in_sensor)
wrench = np.concatenate([s_force,s_torque]) wrench = np.concatenate([s_force,s_torque])
# print("com66666")
# 传感器到TCP # 传感器到TCP
wrench = self.wrench_coordinate_conversion(self.s_tf_matrix_t,wrench) wrench = self.wrench_coordinate_conversion(self.s_tf_matrix_t,wrench)
# 交给ARM STATE集中管理 # 交给ARM STATE集中管理
self.arm_state.external_wrench_tcp = wrench self.arm_state.external_wrench_tcp = wrench
# print("com777777777777777777")
# 对tcp坐标系下的外力外矩进行平滑 # 对tcp坐标系下的外力外矩进行平滑
x_tcp_predict, P_tcp_predict = self.kalman_predict(x = self.x_tcp, x_tcp_predict, P_tcp_predict = self.kalman_predict(x = self.x_tcp,
P = self.P_tcp, P = self.P_tcp,
Q = self.Q_tcp) Q = self.Q_tcp)
# print("com88888888888888888888")
self.x_tcp, self.P_tcp = self.kalman_update(x_predict = x_tcp_predict, self.x_tcp, self.P_tcp = self.kalman_update(x_predict = x_tcp_predict,
P_predict = P_tcp_predict, P_predict = P_tcp_predict,
z = self.arm_state.external_wrench_tcp, z = self.arm_state.external_wrench_tcp,
R = self.R_tcp) R = self.R_tcp)
# print("com999999999999")
self.arm_state.external_wrench_tcp = self.x_tcp self.arm_state.external_wrench_tcp = self.x_tcp
self.arm_state.last_external_wrench_tcp = self.arm_state.external_wrench_tcp self.arm_state.last_external_wrench_tcp = self.arm_state.external_wrench_tcp
# print("update data wrench :", self.arm_state.external_wrench_tcp)
return 0 return 0
def switch_payload(self,name): def switch_payload(self,name):
if name in self.playload_dict: if name in self.playload_dict:
self.stop()
self.current_head = name self.current_head = name
self.logger.log_blue(f"Into switch_payload,change to{name}") self.logger.log_blue(f"Into switch_payload,change to{name}")
@ -665,10 +676,11 @@ class MassageRobot:
if self.arm.is_exit or self.exit_event.is_set(): if self.arm.is_exit or self.exit_event.is_set():
break break
try: try:
self.arm.dashboard.socket_dobot.sendall(tcp_command) # self.arm.dashboard.socket_dobot.sendall(tcp_command)
self.arm.dashboard.ServoPos(pose_processed[0],pose_processed[1],pose_processed[2],pose_processed[3],pose_processed[4],pose_processed[5],t=0.02, aheadtime=20,gain=200)
recv_start_time = time.time() recv_start_time = time.time()
self.arm.dashboard.socket_dobot.recv(1024) # self.arm.dashboard.socket_dobot.recv(1024)
recv_time = time.time() - recv_start_time # recv_time = time.time() - recv_start_time
break break
except Exception as e: except Exception as e:
print(f"发送指令错误:{e}") print(f"发送指令错误:{e}")
@ -762,14 +774,14 @@ class MassageRobot:
self.interrupt_event.clear() self.interrupt_event.clear()
self.arm_control_thread.join() self.arm_control_thread.join()
self.arm_measure_thread.join() self.arm_measure_thread.join()
for i in range(3):
self.force_sensor.disable_active_transmission()
self.force_sensor.start_background_reading()
# clear_time = time.time() # clear_time = time.time()
# self.clear_socket_buffer(self.arm.dashboard.socket_dobot) # self.clear_socket_buffer(self.arm.dashboard.socket_dobot)
# print(f"==={time.time()-clear_time}===") # print(f"==={time.time()-clear_time}===")
def stop(self): def stop(self):
for i in range(3):
self.force_sensor.disable_active_transmission()
self.force_sensor.start_background_reading()
self.arm.stop_motion() self.arm.stop_motion()
self.logger.log_info("MassageRobot停止") self.logger.log_info("MassageRobot停止")

View File

@ -242,12 +242,19 @@ class DobotApi:
with self.__globalLock: with self.__globalLock:
self.send_data(string) self.send_data(string)
send_time = time.time() send_time = time.time()
print(f"send_data:{string}") # print(f"send_data:{string}")
recvData = self.wait_reply() recvData = self.wait_reply()
print(f"===={time.time()-send_time}s====recvData:{string}") print(f"===={time.time()-send_time}s====recvData:{string}")
if not self.ParseResultId(recvData): if not self.ParseResultId(recvData):
return None return None
return recvData return recvData
def sendMsg(self, string):
"""
send Sync
"""
self.send_data(string)
def __del__(self): def __del__(self):
self.close() self.close()
@ -2063,6 +2070,38 @@ class DobotApiDashboard(DobotApi):
string = string + ','+ii string = string + ','+ii
string = string + ')' string = string + ')'
return self.sendRecvMsg(string) return self.sendRecvMsg(string)
def ServoPos(self, X, Y, Z, RX, RY, RZ, t=-1.0,aheadtime=-1.0, gain=-1.0):
"""
参数名 类型 含义 是否必填 参数范围
X double X 轴位置单位毫米
Y double Y 轴位置单位毫米
Z double Z 轴位置单位毫米
Rx double Rx 轴位置单位
Ry double Ry 轴位置单位
Rz double Rz 轴位置单位
t float 该点位的运行时间默认0.1,单位s [0.004,3600.0]
aheadtime float 作用类似于PID的D项默认50标量无单位 [20.0,100.0]
gain float 目标位置的比例放大器作用类似于PID的P项默认500标量无单位 [200.0,1000.0]
Pose string Target point posture variables. The reference coordinate system is the global user and tool coordinate system, see the User and Tool command descriptions in Settings command (the default values are both 0
t float Optional parameter.Running time of the point, unit: s, value range: [0.02,3600.0], default value:0.1
aheadtime float Optional parameter.Advanced time, similar to the D in PID control. Scalar, no unit, valuerange: [20.0,100.0], default value: 50.
gain float Optional parameter.Proportional gain of the target position, similar to the P in PID control.Scalar, no unit, value range: [200.0,1000.0], default value: 500.
"""
string = ""
string = "ServoP({:f},{:f},{:f},{:f},{:f},{:f}".format(X, Y, Z, RX, RY, RZ)
params = []
if t != -1:
params.append('t={:f}'.format(t))
if aheadtime != -1:
params.append('aheadtime={:f}'.format(aheadtime))
if gain != -1:
params.append('gain={:f}'.format(gain))
for ii in params:
string = string + ','+ii
string = string + ')'
return self.sendMsg(string)
def ServoP(self, X, Y, Z, RX, RY, RZ, t=-1.0,aheadtime=-1.0, gain=-1.0): def ServoP(self, X, Y, Z, RX, RY, RZ, t=-1.0,aheadtime=-1.0, gain=-1.0):
""" """
参数名 类型 含义 是否必填 参数范围 参数名 类型 含义 是否必填 参数范围

View File

@ -15,7 +15,7 @@ sys.path.append(os.path.abspath(os.path.join(os.getcwd(), "Massage/MassageContro
class XjcSensor: class XjcSensor:
def __init__(self, port='/dev/ttyS0', baudrate=115200, rate=250): def __init__(self, port='/dev/ttyUSB0', baudrate=115200, rate=250):
self.port = port self.port = port
self.baudrate = baudrate self.baudrate = baudrate
self.rate = rate self.rate = rate
@ -294,6 +294,56 @@ class XjcSensor:
except serial.SerialException as e: except serial.SerialException as e:
print(f"Serial communication error: {e}") print(f"Serial communication error: {e}")
return None return None
# def read(self):
# """
# Read the sensor's data.
# """
# if self.ser is None:
# print("Serial port not initialized.")
# return None
# try:
# # 清空缓冲区
# if self.ser.in_waiting > 0:
# self.ser.read(self.ser.in_waiting)
# # 尝试寻找帧头0x20 0x4E
# for _ in range(100): # 最多尝试100次避免死循环
# if self.ser.in_waiting >= 2:
# byte1 = self.ser.read(1)
# if int.from_bytes(byte1, 'big') == 0x20:
# byte2 = self.ser.read(1)
# if int.from_bytes(byte2, 'big') == 0x4E:
# response = bytearray([0x20, 0x4E])
# break
# else:
# continue
# else:
# print("Frame header not found.")
# return None
# # 读取剩余14个字节
# remaining = self.ser.read(14)
# if len(remaining) < 14:
# print("Incomplete data received.")
# return None
# response.extend(remaining)
# # CRC 校验
# Lo_check, Hi_check = self.crc16(response[:-2])
# if response[-1] != Hi_check or response[-2] != Lo_check:
# print("CRC check failed!")
# return None
# # 数据解析
# sensor_data = self.parse_data_passive(response)
# return sensor_data
# except serial.SerialException as e:
# print(f"Serial communication error: {e}")
# return None
def parse_data_passive(self, buffer): def parse_data_passive(self, buffer):
@ -425,14 +475,14 @@ if __name__ == "__main__":
xjc_sensor.set_zero() xjc_sensor.set_zero()
xjc_sensor.set_zero() xjc_sensor.set_zero()
xjc_sensor.set_zero() xjc_sensor.set_zero()
# time.sleep(1) time.sleep(1)
# xjc_sensor.enable_active_transmission() xjc_sensor.enable_active_transmission()
# while True: while True:
# # sensor_data = xjc_sensor.read() sensor_data = xjc_sensor.read()
# sensor_data = xjc_sensor.read_data_f32() # sensor_data = xjc_sensor.read_data_f32()
# current_time = time.strftime("%Y-%m-%d_%H-%M-%S") current_time = time.strftime("%Y-%m-%d_%H-%M-%S")
# if sensor_data is None: if sensor_data is None:
# print('failed to get force sensor data!') print('failed to get force sensor data!')
# print(f"{current_time}-----{sensor_data}") print(f"{current_time}-----{sensor_data}")
# rate.sleep(False) rate.sleep(False)
# # break # break

View File

@ -180,8 +180,8 @@ class Identifier:
if __name__ == '__main__': if __name__ == '__main__':
arm = dobot_nova5() arm = dobot_nova5()
# arm.start() # arm.start()
arm.setEndEffector(i=9,tool_i="{0.0,0.0,154.071,0.0,0.0,0.0}") # arm.setEndEffector(i=9,tool_i="{0.0,0.0,154.071,0.0,0.0,0.0}")
arm.chooseEndEffector(i=9) # arm.chooseEndEffector(i=9)
arm.init() arm.init()
sensor = XjcSensor() sensor = XjcSensor()
sensor.connect() sensor.connect()
@ -189,9 +189,9 @@ if __name__ == '__main__':
sensor.disable_active_transmission() sensor.disable_active_transmission()
sensor.disable_active_transmission() sensor.disable_active_transmission()
atexit.register(sensor.disconnect) atexit.register(sensor.disconnect)
identifier = Identifier(arm=arm,sensor=sensor,config_path="/home/jsfb/jsfb_ws/global_config/massage_head/shockwave_playload.yaml") identifier = Identifier(arm=arm,sensor=sensor,config_path="/home/jsfb/jsfb_ws/global_config/massage_head/roller_playload.yaml")
ready_pose = [0.403467*1000,-0.1349880*1000,0.423604*1000,-180.0000,-30.0000,0.0042] ready_pose = [0.403467*1000,-0.1349880*1000,0.423604*1000,-180.0000,-30.0000,0.0042]
# ready_pose = [250.0, -135.0, 344.3392, -180.0, 0.0, -90.0] # ready_pose = [250.0, -135.0, 344.3392, -180.0, 0.0, -90.0]
time.sleep(1) time.sleep(1)
identifier.identify_param_auto(ready_pose,15) identifier.identify_param_auto(ready_pose,45)
arm.disableRobot() arm.disableRobot()

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 391 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 393 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 393 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 393 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 395 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 395 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 393 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 395 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 395 KiB

After

Width:  |  Height:  |  Size: 393 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 393 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 393 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 393 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 395 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 395 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 393 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 395 KiB

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 395 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 393 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 396 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 393 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 393 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 393 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 394 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 391 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 392 KiB

After

Width:  |  Height:  |  Size: 392 KiB

Some files were not shown because too many files have changed in this diff Show More