-
Notifications
You must be signed in to change notification settings - Fork 29
/
5006-set_cgpio_digital_analog.cc
51 lines (42 loc) · 1.22 KB
/
5006-set_cgpio_digital_analog.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
/**
* Software License Agreement (MIT License)
*
* Copyright (c) 2022, UFACTORY, Inc.
*
* All rights reserved.
*
* @author Vinman <[email protected]> <[email protected]>
*/
#include "xarm/wrapper/xarm_api.h"
int main(int argc, char **argv) {
if (argc < 2) {
printf("Please enter IP address\n");
return 0;
}
std::string port(argv[1]);
XArmAPI *arm = new XArmAPI(port);
sleep_milliseconds(500);
if (arm->error_code != 0) arm->clean_error();
if (arm->warn_code != 0) arm->clean_warn();
arm->motion_enable(true);
arm->set_mode(0);
arm->set_state(0);
sleep_milliseconds(500);
printf("=========================================\n");
int ret;
for (int i = 0; i < 8; ++i) {
ret = arm->set_cgpio_digital(i, 0);
printf("set_cgpio_digital, ret=%d, io%d=0\n", ret, i);
}
sleep_milliseconds(2000);
ret = arm->set_cgpio_analog(0, (fp32)2.6);
printf("set_cgpio_analog, ret=%d, io=0, val=2.6\n", ret);
ret = arm->set_cgpio_analog(1, (fp32)3.6);
printf("set_cgpio_analog, ret=%d, io=1, val=3.6\n", ret);
sleep_milliseconds(2000);
for (int i = 0; i < 8; ++i) {
ret = arm->set_cgpio_digital(i, 1);
printf("set_cgpio_digital, ret=%d, io%d=1\n", ret, i);
}
return 0;
}