uxbus_cmd.h
Go to the documentation of this file.
1 /* Copyright 2017 UFACTORY Inc. All Rights Reserved.
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Author: Jimy Zhang <jimy92@163.com>
6  ============================================================================*/
7 #ifndef CORE_INSTRUCTION_UXBUS_CMD_H_
8 #define CORE_INSTRUCTION_UXBUS_CMD_H_
9 
10 #include <mutex>
11 #include <iostream>
12 #include <vector>
13 #include <sys/timeb.h>
14 #ifdef _WIN32
15 #include <windows.h>
16 #else
17 #include <unistd.h>
18 #include <time.h>
19 #endif
22 
23 
24 inline void sleep_milliseconds(unsigned long milliseconds) {
25 #ifdef _WIN32
26  Sleep(milliseconds);
27 #else
28  usleep(milliseconds * 1000);
29 #endif
30 }
31 
32 inline long long get_system_time()
33 {
34 #ifdef _WIN32
35  struct timeb t;
36  ftime(&t);
37  return 1000 * t.time + t.millitm; // milliseconds
38 #else
39  struct timespec t;
40  clock_gettime(CLOCK_REALTIME, &t);
41  return 1000 * t.tv_sec + t.tv_nsec / 1000000; // milliseconds
42 #endif
43 }
44 
45 class UxbusCmd {
46 public:
47  UxbusCmd(void);
48  ~UxbusCmd(void);
49 
50  int set_timeout(float timeout);
51 
52  int get_version(unsigned char rx_data[40]);
53  int get_robot_sn(unsigned char rx_data[40]);
54  int check_verification(int *rx_data);
55  int shutdown_system(int value);
56  int set_record_traj(int value);
57  int save_traj(char filename[81]);
58  int load_traj(char filename[81]);
59  int playback_traj(int times, int spdx = 1);
60  int playback_traj_old(int times);
61  int get_traj_rw_status(int *rx_data);
62  int set_reduced_mode(int on_off);
63  int set_reduced_linespeed(float lspd_mm);
64  int set_reduced_jointspeed(float jspd_rad);
65  int get_reduced_mode(int *rx_data);
66  int get_reduced_states(int *on, int xyz_list[6], float *tcp_speed, float *joint_speed, float jrange_rad[14] = NULL, int *fense_is_on = NULL, int *collision_rebound_is_on = NULL, int length = 21);
67  int set_xyz_limits(int xyz_list[6]);
68  int set_world_offset(float pose_offset[6]);
69  int cnter_reset(void);
70  int cnter_plus(void);
71  int set_reduced_jrange(float jrange_rad[14]);
72  int set_fense_on(int on_off);
73  int set_collis_reb(int on_off);
74  int motion_en(int id, int value);
75  int set_state(int value);
76  int get_state(int *rx_data);
77  int get_cmdnum(int *rx_data);
78  int get_err_code(int *rx_data);
79  int get_hd_types(int *rx_data);
80  int reload_dynamics(void);
81  int clean_err(void);
82  int clean_war(void);
83  int set_brake(int axis, int en);
84  int set_mode(int value);
85  int move_line(float mvpose[6], float mvvelo, float mvacc, float mvtime);
86  int move_lineb(float mvpose[6], float mvvelo, float mvacc, float mvtime,
87  float mvradii);
88  int move_joint(float mvjoint[7], float mvvelo, float mvacc, float mvtime);
89  int move_jointb(float mvjoint[7], float mvvelo, float mvacc, float mvradii);
90  int move_line_tool(float mvpose[6], float mvvelo, float mvacc, float mvtime);
91  int move_gohome(float mvvelo, float mvacc, float mvtime);
92  int move_servoj(float mvjoint[7], float mvvelo, float mvacc, float mvtime);
93  int move_servo_cartesian(float mvpose[6], float mvvelo, float mvacc, float mvtime);
94  int set_servot(float jnt_taus[7]);
95  int get_joint_tau(float jnt_taus[7]);
96  int set_safe_level(int level);
97  int get_safe_level(int *level);
98  int sleep_instruction(float sltime);
99  int move_circle(float pose1[6], float pose2[6], float mvvelo, float mvacc, float mvtime, float percent);
100  int set_tcp_jerk(float jerk);
101  int set_tcp_maxacc(float maxacc);
102  int set_joint_jerk(float jerk);
103  int set_joint_maxacc(float maxacc);
104  int set_tcp_offset(float pose_offset[6]);
105  int set_tcp_load(float mass, float load_offset[3]);
106  int set_collis_sens(int value);
107  int set_teach_sens(int value);
108  int set_gravity_dir(float gravity_dir[3]);
109  int clean_conf(void);
110  int save_conf(void);
111 
112  int get_tcp_pose(float pose[6]);
113  int get_joint_pose(float angles[7]);
114  int get_ik(float pose[6], float angles[7]);
115  int get_fk(float angles[7], float pose[6]);
116  int is_joint_limit(float joint[7], int *value);
117  int is_tcp_limit(float pose[6], int *value);
118  int gripper_addr_w16(int addr, float value);
119  int gripper_addr_r16(int addr, float *value);
120  int gripper_addr_w32(int addr, float value);
121  int gripper_addr_r32(int addr, float *value);
122  int gripper_set_en(int value);
123  int gripper_set_mode(int value);
124  int gripper_set_zero(void);
125  int gripper_get_pos(float *pulse);
126  int gripper_set_pos(float pulse);
127  int gripper_set_posspd(float speed);
128  int gripper_get_errcode(int rx_data[2]);
129  int gripper_clean_err(void);
130 
131  int tgpio_addr_w16(int addr, float value);
132  int tgpio_addr_r16(int addr, float *value);
133  int tgpio_addr_w32(int addr, float value);
134  int tgpio_addr_r32(int addr, float *value);
135  int tgpio_get_digital(int *io1, int *io2);
136  int tgpio_set_digital(int ionum, int value);
137  int tgpio_get_analog1(float *value);
138  int tgpio_get_analog2(float *value);
139 
140  int set_modbus_timeout(int value);
141  int set_modbus_baudrate(int baud);
142  int tgpio_set_modbus(unsigned char *send_data, int length, unsigned char *recv_data);
143  int gripper_modbus_w16s(int addr, float value, int len);
144  int gripper_modbus_r16s(int addr, int len, unsigned char *rx_data);
145  int gripper_modbus_set_en(int value);
146  int gripper_modbus_set_mode(int value);
147  int gripper_modbus_set_zero(void);
148  int gripper_modbus_get_pos(float *pulse);
149  int gripper_modbus_set_pos(float pulse);
150  int gripper_modbus_set_posspd(float speed);
151  int gripper_modbus_get_errcode(int *err);
152  int gripper_modbus_clean_err(void);
153 
154  int servo_set_zero(int id);
155  int servo_get_dbmsg(int rx_data[16]);
156  int servo_addr_w16(int id, int addr, float value);
157  int servo_addr_r16(int id, int addr, float *value);
158  int servo_addr_w32(int id, int addr, float value);
159  int servo_addr_r32(int id, int addr, float *value);
160 
161 
162  int cgpio_get_auxdigit(int *value);
163  int cgpio_get_analog1(float *value);
164  int cgpio_get_analog2(float *value);
165  int cgpio_set_auxdigit(int ionum, int value);
166  int cgpio_set_analog1(float value);
167  int cgpio_set_analog2(float value);
168  int cgpio_set_infun(int ionum, int fun);
169  int cgpio_set_outfun(int ionum, int fun);
170  int cgpio_get_state(int *state, int *digit_io, float *analog, int *input_conf, int *output_conf, int *input_conf2=NULL, int *output_conf2=NULL);
171 
172  int get_pose_offset(float pose1[6], float pose2[6], float offset[6], int orient_type_in=0, int orient_type_out=0);
173  int get_position_aa(float pose[6]);
174  int move_line_aa(float mvpose[6], float mvvelo, float mvacc, float mvtime, int mvcoord=0, int relative=0);
175  int move_servo_cart_aa(float mvpose[6], float mvvelo, float mvacc, int tool_coord=0, int relative=0);
176 
177  int tgpio_delay_set_digital(int ionum, int value, float delay_sec);
178  int cgpio_delay_set_digital(int ionum, int value, float delay_sec);
179  int tgpio_position_set_digital(int ionum, int value, float xyz[3], float tol_r);
180  int cgpio_position_set_digital(int ionum, int value, float xyz[3], float tol_r);
181  int cgpio_position_set_analog(int ionum, float value, float xyz[3], float tol_r);
182  int config_io_stop_reset(int io_type, int val);
183 
184  int set_report_tau_or_i(int tau_or_i);
185  int get_report_tau_or_i(int *rx_data);
186 
187  int set_self_collision_detection(int on_off);
188  int set_collision_tool_model(int tool_type, int n = 0, float *argv = NULL);
189  int set_simulation_robot(int on_off);
190 
191  int vc_set_jointv(float jnt_v[7], int jnt_sync);
192  int vc_set_linev(float line_v[6], int coord);
193 
194  virtual void close(void);
195  virtual int is_ok(void);
196 
197 private:
198  virtual int check_xbus_prot(unsigned char *data, int funcode);
199  virtual int send_pend(int funcode, int num, int timeout, unsigned char *rx_data);
200  virtual int send_xbus(int funcode, unsigned char *txdata, int num);
201  int set_nu8_char(int funcode, char *datas, int num);
202  int set_nu8(int funcode, int *datas, int num);
203  int get_nu8(int funcode, int *rx_data, int num);
204  int get_nu8(int funcode, unsigned char *rx_data, int num);
205  int set_nu16(int funcode, int *datas, int num);
206  int get_nu16(int funcode, int *rx_data, int num);
207  int set_nfp32(int funcode, float *datas, int num);
208  int set_nint32(int funcode, int *datas, int num);
209  int get_nfp32(int funcode, float *rx_data, int num);
210  int swop_nfp32(int funcode, float tx_datas[], int txn, float *rx_data, int rxn);
211  int is_nfp32(int funcode, float datas[], int txn, int *value);
212  int set_nfp32_with_bytes(int funcode, float *datas, int num, char *additional, int n);
213 
214 public:
216 
217 private:
218  std::mutex mutex_;
221 };
222 
223 #endif
int set_gravity_dir(float gravity_dir[3])
Definition: uxbus_cmd.cc:506
int get_reduced_states(int *on, int xyz_list[6], float *tcp_speed, float *joint_speed, float jrange_rad[14]=NULL, int *fense_is_on=NULL, int *collision_rebound_is_on=NULL, int length=21)
Definition: uxbus_cmd.cc:256
int set_collis_sens(int value)
Definition: uxbus_cmd.cc:498
int set_nfp32_with_bytes(int funcode, float *datas, int num, char *additional, int n)
Definition: uxbus_cmd.cc:178
int set_nu8(int funcode, int *datas, int num)
Definition: uxbus_cmd.cc:64
int gripper_set_posspd(float speed)
Definition: uxbus_cmd.cc:623
int gripper_addr_r16(int addr, float *value)
Definition: uxbus_cmd.cc:558
void sleep_milliseconds(unsigned long milliseconds)
Definition: uxbus_cmd.h:24
int gripper_modbus_set_pos(float pulse)
Definition: uxbus_cmd.cc:828
int set_joint_maxacc(float maxacc)
Definition: uxbus_cmd.cc:484
int get_err_code(int *rx_data)
Definition: uxbus_cmd.cc:319
int get_version(unsigned char rx_data[40])
Definition: uxbus_cmd.cc:194
int gripper_modbus_clean_err(void)
Definition: uxbus_cmd.cc:855
int set_safe_level(int level)
Definition: uxbus_cmd.cc:440
int save_conf(void)
Definition: uxbus_cmd.cc:514
int tgpio_get_analog1(float *value)
Definition: uxbus_cmd.cc:720
int set_timeout(float timeout)
Definition: uxbus_cmd.cc:40
int playback_traj_old(int times)
Definition: uxbus_cmd.cc:220
int cgpio_get_analog2(float *value)
Definition: uxbus_cmd.cc:942
int gripper_set_mode(int value)
Definition: uxbus_cmd.cc:607
int move_jointb(float mvjoint[7], float mvvelo, float mvacc, float mvradii)
Definition: uxbus_cmd.cc:386
bool state_is_ready
Definition: uxbus_cmd.h:215
int set_nu8_char(int funcode, char *datas, int num)
Definition: uxbus_cmd.cc:51
int clean_war(void)
Definition: uxbus_cmd.cc:337
int SET_TIMEOUT_
Definition: uxbus_cmd.h:220
static const int GET_TIMEOUT
int move_lineb(float mvpose[6], float mvvelo, float mvacc, float mvtime, float mvradii)
Definition: uxbus_cmd.cc:364
int get_hd_types(int *rx_data)
Definition: uxbus_cmd.cc:323
int set_tcp_maxacc(float maxacc)
Definition: uxbus_cmd.cc:474
int get_report_tau_or_i(int *rx_data)
Definition: uxbus_cmd.cc:1158
int get_nu16(int funcode, int *rx_data, int num)
Definition: uxbus_cmd.cc:103
int set_mode(int value)
Definition: uxbus_cmd.cc:347
int set_world_offset(float pose_offset[6])
Definition: uxbus_cmd.cc:276
int config_io_stop_reset(int io_type, int val)
Definition: uxbus_cmd.cc:1148
int set_reduced_jrange(float jrange_rad[14])
Definition: uxbus_cmd.cc:288
int servo_get_dbmsg(int rx_data[16])
Definition: uxbus_cmd.cc:866
virtual int check_xbus_prot(unsigned char *data, int funcode)
Definition: uxbus_cmd.cc:28
int shutdown_system(int value)
Definition: uxbus_cmd.cc:206
int gripper_get_errcode(int rx_data[2])
Definition: uxbus_cmd.cc:627
int get_fk(float angles[7], float pose[6])
Definition: uxbus_cmd.cc:530
int gripper_modbus_w16s(int addr, float value, int len)
Definition: uxbus_cmd.cc:774
int load_traj(char filename[81])
Definition: uxbus_cmd.cc:229
int vc_set_linev(float line_v[6], int coord)
Definition: uxbus_cmd.cc:1189
int gripper_modbus_set_zero(void)
Definition: uxbus_cmd.cc:816
int get_state(int *rx_data)
Definition: uxbus_cmd.cc:311
int set_xyz_limits(int xyz_list[6])
Definition: uxbus_cmd.cc:272
int is_tcp_limit(float pose[6], int *value)
Definition: uxbus_cmd.cc:538
int tgpio_get_digital(int *io1, int *io2)
Definition: uxbus_cmd.cc:695
int reload_dynamics(void)
Definition: uxbus_cmd.cc:327
int set_reduced_jointspeed(float jspd_rad)
Definition: uxbus_cmd.cc:247
int set_servot(float jnt_taus[7])
Definition: uxbus_cmd.cc:430
int save_traj(char filename[81])
Definition: uxbus_cmd.cc:225
int set_collision_tool_model(int tool_type, int n=0, float *argv=NULL)
Definition: uxbus_cmd.cc:1167
int set_nint32(int funcode, int *datas, int num)
Definition: uxbus_cmd.cc:126
int get_joint_pose(float angles[7])
Definition: uxbus_cmd.cc:522
int move_circle(float pose1[6], float pose2[6], float mvvelo, float mvacc, float mvtime, float percent)
Definition: uxbus_cmd.cc:454
int gripper_clean_err(void)
Definition: uxbus_cmd.cc:631
int move_servo_cartesian(float mvpose[6], float mvvelo, float mvacc, float mvtime)
Definition: uxbus_cmd.cc:421
int is_joint_limit(float joint[7], int *value)
Definition: uxbus_cmd.cc:534
int swop_nfp32(int funcode, float tx_datas[], int txn, float *rx_data, int rxn)
Definition: uxbus_cmd.cc:148
int set_nu16(int funcode, int *datas, int num)
Definition: uxbus_cmd.cc:92
int cgpio_get_state(int *state, int *digit_io, float *analog, int *input_conf, int *output_conf, int *input_conf2=NULL, int *output_conf2=NULL)
Definition: uxbus_cmd.cc:1007
int playback_traj(int times, int spdx=1)
Definition: uxbus_cmd.cc:215
int get_traj_rw_status(int *rx_data)
Definition: uxbus_cmd.cc:233
int cgpio_position_set_analog(int ionum, float value, float xyz[3], float tol_r)
Definition: uxbus_cmd.cc:1133
int move_line_aa(float mvpose[6], float mvvelo, float mvacc, float mvtime, int mvcoord=0, int relative=0)
Definition: uxbus_cmd.cc:1059
int get_robot_sn(unsigned char rx_data[40])
Definition: uxbus_cmd.cc:198
int tgpio_addr_w16(int addr, float value)
Definition: uxbus_cmd.cc:638
int servo_addr_r16(int id, int addr, float *value)
Definition: uxbus_cmd.cc:883
int move_gohome(float mvvelo, float mvacc, float mvtime)
Definition: uxbus_cmd.cc:404
int get_ik(float pose[6], float angles[7])
Definition: uxbus_cmd.cc:526
int get_nu8(int funcode, int *rx_data, int num)
Definition: uxbus_cmd.cc:77
int gripper_modbus_set_en(int value)
Definition: uxbus_cmd.cc:800
int tgpio_set_modbus(unsigned char *send_data, int length, unsigned char *recv_data)
Definition: uxbus_cmd.cc:760
int set_modbus_timeout(int value)
Definition: uxbus_cmd.cc:739
int check_verification(int *rx_data)
Definition: uxbus_cmd.cc:202
int cnter_plus(void)
Definition: uxbus_cmd.cc:284
int get_nfp32(int funcode, float *rx_data, int num)
Definition: uxbus_cmd.cc:137
int gripper_modbus_get_errcode(int *err)
Definition: uxbus_cmd.cc:847
int set_simulation_robot(int on_off)
Definition: uxbus_cmd.cc:1178
int servo_addr_w32(int id, int addr, float value)
Definition: uxbus_cmd.cc:899
int cgpio_set_infun(int ionum, int fun)
Definition: uxbus_cmd.cc:979
int get_position_aa(float pose[6])
Definition: uxbus_cmd.cc:1055
int cgpio_set_auxdigit(int ionum, int value)
Definition: uxbus_cmd.cc:948
int get_pose_offset(float pose1[6], float pose2[6], float offset[6], int orient_type_in=0, int orient_type_out=0)
Definition: uxbus_cmd.cc:1035
int gripper_modbus_set_posspd(float speed)
Definition: uxbus_cmd.cc:839
int gripper_set_pos(float pulse)
Definition: uxbus_cmd.cc:619
int set_tcp_offset(float pose_offset[6])
Definition: uxbus_cmd.cc:489
int GET_TIMEOUT_
Definition: uxbus_cmd.h:219
int set_fense_on(int on_off)
Definition: uxbus_cmd.cc:292
virtual int send_pend(int funcode, int num, int timeout, unsigned char *rx_data)
Definition: uxbus_cmd.cc:30
int tgpio_addr_r32(int addr, float *value)
Definition: uxbus_cmd.cc:679
int set_modbus_baudrate(int baud)
Definition: uxbus_cmd.cc:743
int gripper_modbus_r16s(int addr, int len, unsigned char *rx_data)
Definition: uxbus_cmd.cc:789
int gripper_modbus_set_mode(int value)
Definition: uxbus_cmd.cc:808
int servo_set_zero(int id)
Definition: uxbus_cmd.cc:862
int tgpio_get_analog2(float *value)
Definition: uxbus_cmd.cc:727
virtual void close(void)
Definition: uxbus_cmd.cc:36
int set_collis_reb(int on_off)
Definition: uxbus_cmd.cc:297
int get_safe_level(int *level)
Definition: uxbus_cmd.cc:445
int get_tcp_pose(float pose[6])
Definition: uxbus_cmd.cc:518
int gripper_addr_r32(int addr, float *value)
Definition: uxbus_cmd.cc:587
long long get_system_time()
Definition: uxbus_cmd.h:32
int set_state(int value)
Definition: uxbus_cmd.cc:307
int gripper_set_zero(void)
Definition: uxbus_cmd.cc:611
int cgpio_get_auxdigit(int *value)
Definition: uxbus_cmd.cc:933
int gripper_get_pos(float *pulse)
Definition: uxbus_cmd.cc:615
int move_line_tool(float mvpose[6], float mvvelo, float mvacc, float mvtime)
Definition: uxbus_cmd.cc:395
int sleep_instruction(float sltime)
Definition: uxbus_cmd.cc:449
int get_joint_tau(float jnt_taus[7])
Definition: uxbus_cmd.cc:436
int clean_err(void)
Definition: uxbus_cmd.cc:332
int move_line(float mvpose[6], float mvvelo, float mvacc, float mvtime)
Definition: uxbus_cmd.cc:355
int clean_conf(void)
Definition: uxbus_cmd.cc:510
UxbusCmd(void)
Definition: uxbus_cmd.cc:22
int get_cmdnum(int *rx_data)
Definition: uxbus_cmd.cc:315
int tgpio_addr_r16(int addr, float *value)
Definition: uxbus_cmd.cc:651
int set_tcp_jerk(float jerk)
Definition: uxbus_cmd.cc:469
~UxbusCmd(void)
Definition: uxbus_cmd.cc:26
int servo_addr_r32(int id, int addr, float *value)
Definition: uxbus_cmd.cc:912
int servo_addr_w16(int id, int addr, float value)
Definition: uxbus_cmd.cc:870
int cgpio_position_set_digital(int ionum, int value, float xyz[3], float tol_r)
Definition: uxbus_cmd.cc:1119
int set_record_traj(int value)
Definition: uxbus_cmd.cc:210
int move_servoj(float mvjoint[7], float mvvelo, float mvacc, float mvtime)
Definition: uxbus_cmd.cc:412
int cnter_reset(void)
Definition: uxbus_cmd.cc:280
int is_nfp32(int funcode, float datas[], int txn, int *value)
Definition: uxbus_cmd.cc:163
int tgpio_position_set_digital(int ionum, int value, float xyz[3], float tol_r)
Definition: uxbus_cmd.cc:1105
int gripper_modbus_get_pos(float *pulse)
Definition: uxbus_cmd.cc:820
int tgpio_addr_w32(int addr, float value)
Definition: uxbus_cmd.cc:666
int set_reduced_mode(int on_off)
Definition: uxbus_cmd.cc:237
int set_teach_sens(int value)
Definition: uxbus_cmd.cc:502
static const int SET_TIMEOUT
int move_joint(float mvjoint[7], float mvvelo, float mvacc, float mvtime)
Definition: uxbus_cmd.cc:376
int set_reduced_linespeed(float lspd_mm)
Definition: uxbus_cmd.cc:242
int get_reduced_mode(int *rx_data)
Definition: uxbus_cmd.cc:252
int set_nfp32(int funcode, float *datas, int num)
Definition: uxbus_cmd.cc:114
int set_self_collision_detection(int on_off)
Definition: uxbus_cmd.cc:1162
int gripper_addr_w16(int addr, float value)
Definition: uxbus_cmd.cc:545
int vc_set_jointv(float jnt_v[7], int jnt_sync)
Definition: uxbus_cmd.cc:1182
int set_tcp_load(float mass, float load_offset[3])
Definition: uxbus_cmd.cc:493
int set_joint_jerk(float jerk)
Definition: uxbus_cmd.cc:479
int gripper_addr_w32(int addr, float value)
Definition: uxbus_cmd.cc:574
int move_servo_cart_aa(float mvpose[6], float mvvelo, float mvacc, int tool_coord=0, int relative=0)
Definition: uxbus_cmd.cc:1069
int cgpio_set_outfun(int ionum, int fun)
Definition: uxbus_cmd.cc:983
int motion_en(int id, int value)
Definition: uxbus_cmd.cc:302
int cgpio_set_analog2(float value)
Definition: uxbus_cmd.cc:974
virtual int send_xbus(int funcode, unsigned char *txdata, int num)
Definition: uxbus_cmd.cc:34
int cgpio_get_analog1(float *value)
Definition: uxbus_cmd.cc:936
int cgpio_delay_set_digital(int ionum, int value, float delay_sec)
Definition: uxbus_cmd.cc:1092
virtual int is_ok(void)
Definition: uxbus_cmd.cc:38
int set_report_tau_or_i(int tau_or_i)
Definition: uxbus_cmd.cc:1153
int gripper_set_en(int value)
Definition: uxbus_cmd.cc:603
std::mutex mutex_
Definition: uxbus_cmd.h:218
int set_brake(int axis, int en)
Definition: uxbus_cmd.cc:342
int cgpio_set_analog1(float value)
Definition: uxbus_cmd.cc:969
int tgpio_delay_set_digital(int ionum, int value, float delay_sec)
Definition: uxbus_cmd.cc:1079
int tgpio_set_digital(int ionum, int value)
Definition: uxbus_cmd.cc:704


xarm_api
Author(s):
autogenerated on Sat May 8 2021 02:51:23