-
Notifications
You must be signed in to change notification settings - Fork 115
/
Copy pathb2_stand_example.cpp
350 lines (302 loc) · 10.3 KB
/
b2_stand_example.cpp
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
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
#include <iostream>
#include <stdio.h>
#include <stdint.h>
#include <math.h>
#include <unitree/robot/channel/channel_publisher.hpp>
#include <unitree/robot/channel/channel_subscriber.hpp>
#include <unitree/idl/go2/LowState_.hpp>
#include <unitree/idl/go2/LowCmd_.hpp>
#include <unitree/common/time/time_tool.hpp>
#include <unitree/common/thread/thread.hpp>
#include <unitree/robot/b2/motion_switcher/motion_switcher_client.hpp>
using namespace unitree::common;
using namespace unitree::robot;
using namespace unitree::robot::b2;
#define TOPIC_LOWCMD "rt/lowcmd"
#define TOPIC_LOWSTATE "rt/lowstate"
constexpr double PosStopF = (2.146E+9f);
constexpr double VelStopF = (16000.0f);
class Custom
{
public:
explicit Custom(){}
~Custom(){}
void Init();
void Start();
private:
void InitLowCmd();
void LowStateMessageHandler(const void* messages);
void LowCmdWrite();
int queryMotionStatus();
std::string queryServiceName(std::string form,std::string name);
private:
float Kp = 1000.0;
float Kd = 10.0;
double time_consume = 0;
int rate_count = 0;
int sin_count = 0;
int motiontime = 0;
float dt = 0.002; // 0.001~0.01
MotionSwitcherClient msc;
unitree_go::msg::dds_::LowCmd_ low_cmd{}; // default init
unitree_go::msg::dds_::LowState_ low_state{}; // default init
/*publisher*/
ChannelPublisherPtr<unitree_go::msg::dds_::LowCmd_> lowcmd_publisher;
/*subscriber*/
ChannelSubscriberPtr<unitree_go::msg::dds_::LowState_> lowstate_subscriber;
/*LowCmd write thread*/
ThreadPtr lowCmdWriteThreadPtr;
float _targetPos_1[12] = {0.0, 1.36, -2.65, 0.0, 1.36, -2.65,
0.2, 1.36, -2.65, 0.2, 1.36, -2.65};
float _targetPos_2[12] = {0.0, 0.67, -1.3, 0.0, 0.67, -1.3,
0.0, 0.67, -1.3, 0.0, 0.67, -1.3};
float _targetPos_3[12] = {0.0, 1.36, -2.65, 0.0, 1.36, -2.65,
0.0, 1.36, -2.65, 0.0, 1.36, -2.65};
float _targetPos_4[12] = {-0.5, 1.36, -2.65, 0.5, 1.36, -2.65,
-0.5, 1.36, -2.65, 0.5, 1.36, -2.65};
float _startPos[12];
float _duration_1 = 500;
float _duration_2 = 900;
float _duration_3 = 1000;
float _duration_4 = 1100;
float _duration_5 = 500;
float _percent_1 = 0;
float _percent_2 = 0;
float _percent_3 = 0;
float _percent_4 = 0;
float _percent_5 = 0;
bool firstRun = true;
bool done = false;
};
uint32_t crc32_core(uint32_t* ptr, uint32_t len)
{
unsigned int xbit = 0;
unsigned int data = 0;
unsigned int CRC32 = 0xFFFFFFFF;
const unsigned int dwPolynomial = 0x04c11db7;
for (unsigned int i = 0; i < len; i++)
{
xbit = 1 << 31;
data = ptr[i];
for (unsigned int bits = 0; bits < 32; bits++)
{
if (CRC32 & 0x80000000)
{
CRC32 <<= 1;
CRC32 ^= dwPolynomial;
}
else
{
CRC32 <<= 1;
}
if (data & xbit)
CRC32 ^= dwPolynomial;
xbit >>= 1;
}
}
return CRC32;
}
void Custom::Init()
{
InitLowCmd();
/*create publisher*/
lowcmd_publisher.reset(new ChannelPublisher<unitree_go::msg::dds_::LowCmd_>(TOPIC_LOWCMD));
lowcmd_publisher->InitChannel();
/*create subscriber*/
lowstate_subscriber.reset(new ChannelSubscriber<unitree_go::msg::dds_::LowState_>(TOPIC_LOWSTATE));
lowstate_subscriber->InitChannel(std::bind(&Custom::LowStateMessageHandler, this, std::placeholders::_1), 1);
/*init MotionSwitcherClient*/
msc.SetTimeout(10.0f);
msc.Init();
/*Shut down motion control-related service*/
while(queryMotionStatus())
{
std::cout << "Try to deactivate the motion control-related service." << std::endl;
int32_t ret = msc.ReleaseMode();
if (ret == 0) {
std::cout << "ReleaseMode succeeded." << std::endl;
} else {
std::cout << "ReleaseMode failed. Error code: " << ret << std::endl;
}
sleep(5);
}
}
void Custom::InitLowCmd()
{
low_cmd.head()[0] = 0xFE;
low_cmd.head()[1] = 0xEF;
low_cmd.level_flag() = 0xFF;
low_cmd.gpio() = 0;
for(int i=0; i<20; i++)
{
low_cmd.motor_cmd()[i].mode() = (0x0A); // motor switch to servo (PMSM) mode
low_cmd.motor_cmd()[i].q() = (PosStopF);
low_cmd.motor_cmd()[i].kp() = (0);
low_cmd.motor_cmd()[i].dq() = (VelStopF);
low_cmd.motor_cmd()[i].kd() = (0);
low_cmd.motor_cmd()[i].tau() = (0);
}
}
int Custom::queryMotionStatus()
{
std::string robotForm,motionName;
int motionStatus;
int32_t ret = msc.CheckMode(robotForm,motionName);
if (ret == 0) {
std::cout << "CheckMode succeeded." << std::endl;
} else {
std::cout << "CheckMode failed. Error code: " << ret << std::endl;
}
if(motionName.empty())
{
std::cout << "The motion control-related service is deactivated." << std::endl;
motionStatus = 0;
}
else
{
std::string serviceName = queryServiceName(robotForm,motionName);
std::cout << "Service: "<< serviceName<< " is active" << std::endl;
motionStatus = 1;
}
return motionStatus;
}
std::string Custom::queryServiceName(std::string form,std::string name)
{
if(form == "0")
{
if(name == "normal" ) return "sport_mode";
if(name == "ai" ) return "ai_sport";
if(name == "advanced" ) return "advanced_sport";
}
else
{
if(name == "ai-w" ) return "wheeled_sport(go2W)";
if(name == "normal-w" ) return "wheeled_sport(b2W)";
}
return "";
}
void Custom::Start()
{
/*loop publishing thread*/
lowCmdWriteThreadPtr = CreateRecurrentThreadEx("writebasiccmd", UT_CPU_ID_NONE, 2000, &Custom::LowCmdWrite, this);
}
void Custom::LowStateMessageHandler(const void* message)
{
low_state = *(unitree_go::msg::dds_::LowState_*)message;
}
void Custom::LowCmdWrite()
{
if(_percent_5<1)
{
std::cout<<"Read sensor data example: "<<std::endl;
std::cout<<"Joint 0 pos: "<<low_state.motor_state()[0].q()<<std::endl;
std::cout<<"Imu accelerometer : "<<"x: "<<low_state.imu_state().accelerometer()[0]<<" y: "<<low_state.imu_state().accelerometer()[1]<<" z: "<<low_state.imu_state().accelerometer()[2]<<std::endl;
std::cout<<"Foot force "<<low_state.foot_force()[0]<<std::endl;
std::cout<<std::endl;
}
if((_percent_5 == 1) && ( done == false))
{
std::cout<<"The example is done! "<<std::endl;
std::cout<<std::endl;
done = true;
}
motiontime++;
if(motiontime>=500)
{
if(firstRun)
{
for(int i = 0; i < 12; i++)
{
_startPos[i] = low_state.motor_state()[i].q();
}
firstRun = false;
}
_percent_1 += (float)1 / _duration_1;
_percent_1 = _percent_1 > 1 ? 1 : _percent_1;
if (_percent_1 < 1)
{
for (int j = 0; j < 12; j++)
{
low_cmd.motor_cmd()[j].q() = (1 - _percent_1) * _startPos[j] + _percent_1 * _targetPos_1[j];
low_cmd.motor_cmd()[j].dq() = 0;
low_cmd.motor_cmd()[j].kp() = Kp;
low_cmd.motor_cmd()[j].kd() = Kd;
low_cmd.motor_cmd()[j].tau() = 0;
}
}
if ((_percent_1 == 1)&&(_percent_2 < 1))
{
_percent_2 += (float)1 / _duration_2;
_percent_2 = _percent_2 > 1 ? 1 : _percent_2;
for (int j = 0; j < 12; j++)
{
low_cmd.motor_cmd()[j].q() = (1 - _percent_2) * _targetPos_1[j] + _percent_2 * _targetPos_2[j];
low_cmd.motor_cmd()[j].dq() = 0;
low_cmd.motor_cmd()[j].kp() = Kp;
low_cmd.motor_cmd()[j].kd() = Kd;
low_cmd.motor_cmd()[j].tau() = 0;
}
}
if ((_percent_1 == 1)&&(_percent_2 == 1)&&(_percent_3<1))
{
_percent_3 += (float)1 / _duration_3;
_percent_3 = _percent_3 > 1 ? 1 : _percent_3;
for (int j = 0; j < 12; j++)
{
low_cmd.motor_cmd()[j].q() = _targetPos_2[j];
low_cmd.motor_cmd()[j].dq() = 0;
low_cmd.motor_cmd()[j].kp() = Kp;
low_cmd.motor_cmd()[j].kd() = Kd;
low_cmd.motor_cmd()[j].tau() = 0;
}
}
if ((_percent_1 == 1)&&(_percent_2 == 1)&&(_percent_3==1)&&(_percent_4<1))
{
_percent_4 += (float)1 / _duration_4;
_percent_4 = _percent_4 > 1 ? 1 : _percent_4;
for (int j = 0; j < 12; j++)
{
low_cmd.motor_cmd()[j].q() = (1 - _percent_4) * _targetPos_2[j] + _percent_4 * _targetPos_3[j];
low_cmd.motor_cmd()[j].dq() = 0;
low_cmd.motor_cmd()[j].kp() = Kp;
low_cmd.motor_cmd()[j].kd() = Kd;
low_cmd.motor_cmd()[j].tau() = 0;
}
}
if ((_percent_1 == 1)&&(_percent_2 == 1)&&(_percent_3==1)&&(_percent_4==1)&&((_percent_5<=1)))
{
_percent_5 += (float)1 / _duration_5;
_percent_5 = _percent_5 > 1 ? 1 : _percent_5;
for (int j = 0; j < 12; j++)
{
low_cmd.motor_cmd()[j].q() = (1 - _percent_5) * _targetPos_3[j] + _percent_5 * _targetPos_4[j];
low_cmd.motor_cmd()[j].dq() = 0;
low_cmd.motor_cmd()[j].kp() = Kp;
low_cmd.motor_cmd()[j].kd() = Kd;
low_cmd.motor_cmd()[j].tau() = 0;
}
}
low_cmd.crc() = crc32_core((uint32_t *)&low_cmd, (sizeof(unitree_go::msg::dds_::LowCmd_)>>2)-1);
lowcmd_publisher->Write(low_cmd);
}
}
int main(int argc, const char** argv)
{
if (argc < 2)
{
std::cout << "Usage: " << argv[0] << " networkInterface" << std::endl;
exit(-1);
}
std::cout << "WARNING: Make sure the robot is lying on the ground." << std::endl
<< "Press Enter to continue..." << std::endl;
std::cin.ignore();
ChannelFactory::Instance()->Init(0, argv[1]);
Custom custom;
custom.Init();
custom.Start();
while (1)
{
sleep(10);
}
return 0;
}