-
Notifications
You must be signed in to change notification settings - Fork 0
/
main.cpp
executable file
·2238 lines (1629 loc) · 82.3 KB
/
main.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
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#include "iostream"
#include "../lopt.h"
#include "gazebo_msgs/ModelStates.h"
#include "sensor_msgs/JointState.h"
#include <tf/tf.h>
#include "tf_conversions/tf_eigen.h"
#include <cstdlib>
#include <iostream>
#include <cmath>
#include <Eigen/Core>
// iDynTree headers
#include <iDynTree/Model/FreeFloatingState.h>
#include <iDynTree/KinDynComputations.h>
#include <iDynTree/ModelIO/ModelLoader.h>
#include <iDynTree/Core/EigenHelpers.h>
#include <ros/package.h>
#include "std_msgs/Float64MultiArray.h"
#include "boost/thread.hpp"
#include "gazebo_msgs/SetModelState.h"
#include "gazebo_msgs/SetModelConfiguration.h"
#include <std_srvs/Empty.h>
#include "gazebo_msgs/ContactsState.h"
#include <towr/nlp_formulation.h>
#include <ifopt/ipopt_solver.h>
#include <towr/terrain/examples/height_map_examples.h>
#include <towr/nlp_formulation.h>
#include <ifopt/ipopt_solver.h>
#include <towr/initialization/gait_generator.h>
#include <mutex>
#include "../topt.h"
std::mutex update_mutex;
std::mutex jstate_mutex;
std::mutex wpos_mutex;
using namespace std;
enum SWING_LEGS { L1, L2, L3}; // 4 legs, br-fl, bl-fr
enum SWING_LEG { BR, FL, BL, FR}; // 4 legs, br-fl, bl-fr
class DOGCTRL {
public:
DOGCTRL();
void jointStateCallback(const sensor_msgs::JointState & msg);
void modelStateCallback(const gazebo_msgs::ModelStates & msg);
void eebr_cb(gazebo_msgs::ContactsStateConstPtr eebr);
void eebl_cb(gazebo_msgs::ContactsStateConstPtr eebl);
void eefr_cb(gazebo_msgs::ContactsStateConstPtr eefr);
void eefl_cb(gazebo_msgs::ContactsStateConstPtr eefl);
void run();
void update(Eigen::Matrix4d &eigenWorld_H_base, Eigen::Matrix<double,12,1> &eigenJointPos, Eigen::Matrix<double,12,1> &eigenJointVel, Eigen::Matrix<double,6,1> &eigenBasevel, Eigen::Vector3d &eigenGravity);
//Create the robot
void createrobot(std::string modelFile);
// Compute the Jacobian
void computeJac();
void ComputeJaclinear();
// Compute matrix transformation T needed to recompute matrices/vecotor after the coordinate transform to the CoM
void computeTransformation(const Eigen::VectorXd &Vel_);
void computeJacDotQDot();
void computeJdqdCOMlinear();
void ctrl_loop();
private:
ros::NodeHandle _nh;
ros::Subscriber _joint_state_sub;
ros::Subscriber _model_state_sub;
ros::Publisher _joint_pub;
ros::Subscriber _eebl_sub;
ros::Subscriber _eebr_sub;
ros::Subscriber _eefl_sub;
ros::Subscriber _eefr_sub;
Eigen::Matrix<double,12,1> _jnt_pos;
Eigen::Matrix<double,12,1> _jnt_vel;
Eigen::Matrix4d _world_H_base;
Eigen::Matrix<double,6,1> _base_pos;
Eigen::Matrix<double,6,1> _base_vel;
string _model_name;
// Solve quadratic problem for contact forces
Eigen::VectorXd qpproblem( Eigen::Matrix<double,6,1> &Wcom_des, Eigen::Matrix<double,12,1> &fext);
Eigen::VectorXd qpproblemtr( Eigen::Matrix<double,6,1> &Wcom_des, Eigen::VectorXd vdotswdes, SWING_LEGS swinglegs, Eigen::Matrix<double,12,1> &fext);
Eigen::VectorXd qpproblemol( Eigen::Matrix<double,6,1> &Wcom_des, Eigen::Vector3d vdotswdes, SWING_LEG swingleg, Eigen::Matrix<double,12,1> &fext);
// get function
Eigen::VectorXd getBiasMatrix();
Eigen::VectorXd getGravityMatrix();
Eigen::MatrixXd getMassMatrix();
Eigen::MatrixXd getJacobian();
Eigen::MatrixXd getBiasAcc();
Eigen::MatrixXd getTransMatrix();
Eigen::VectorXd getBiasMatrixCOM();
Eigen::VectorXd getGravityMatrixCOM();
Eigen::MatrixXd getMassMatrixCOM();
Eigen::MatrixXd getMassMatrixCOM_com();
Eigen::MatrixXd getMassMatrixCOM_joints();
Eigen::MatrixXd getJacobianCOM();
Eigen::MatrixXd getJacobianCOM_linear();
Eigen::MatrixXd getBiasAccCOM();
Eigen::MatrixXd getBiasAccCOM_linear();
Eigen::MatrixXd getCOMpos();
Eigen::MatrixXd getCOMvel();
Eigen::MatrixXd getBRpos();
Eigen::MatrixXd getBLpos();
Eigen::MatrixXd getFLpos();
Eigen::MatrixXd getFRpos();
Eigen::MatrixXd getBRvel();
Eigen::MatrixXd getBLvel();
Eigen::MatrixXd getFLvel();
Eigen::MatrixXd getFRvel();
Eigen::MatrixXd getfest();
Eigen::Matrix<double,3,3> getBRworldtransform();
Eigen::Matrix<double,3,3> getBLworldtransform();
Eigen::Matrix<double,3,3> getFLworldtransform();
Eigen::Matrix<double,3,3> getFRworldtransform();
Eigen::Matrix<double,3,1> getbrlowerleg();
double getMass();
int getDoFsnumber();
Eigen::MatrixXd getCtq();
Eigen::MatrixXd getsolution();
// int for DoFs number
unsigned int n;
// Total mass of the robot
double robot_mass;
// KinDynComputations element
iDynTree::KinDynComputations kinDynComp;
// world to floating base transformation
iDynTree::Transform world_H_base;
// Joint position
iDynTree::VectorDynSize jointPos;
// Floating base velocity
iDynTree::Twist baseVel;
// Joint velocity
iDynTree::VectorDynSize jointVel;
// Gravity acceleration
iDynTree::Vector3 gravity;
// Position vector base+joints
iDynTree::VectorDynSize qb;
// Velocity vector base+joints
iDynTree::VectorDynSize dqb;
// Position vector COM+joints
iDynTree::VectorDynSize q;
// Velocity vector COM+joints
iDynTree::VectorDynSize dq;
// Joints limit vector
iDynTree::VectorDynSize qmin;
iDynTree::VectorDynSize qmax;
// Center of Mass Position
iDynTree::Vector6 CoM;
// Center of mass velocity
iDynTree::Vector6 CoM_vel;
//Mass matrix
iDynTree::FreeFloatingMassMatrix MassMatrix;
//Bias Matrix
iDynTree::VectorDynSize Bias;
//Gravity Matrix
iDynTree::MatrixDynSize GravMatrix;
// Jacobian
iDynTree::MatrixDynSize Jac;
// Jacobian derivative
iDynTree::MatrixDynSize JacDot;
//CoM Jacobian
iDynTree::MatrixDynSize Jcom;
// Bias acceleration J_dot*q_dot
iDynTree::MatrixDynSize Jdqd;
// Transformation Matrix
iDynTree::MatrixDynSize T;
// Transformation matrix time derivative
iDynTree::MatrixDynSize T_inv_dot;
//Model
iDynTree::Model model;
iDynTree::ModelLoader mdlLoader;
//Mass matrix in CoM representation
iDynTree::FreeFloatingMassMatrix MassMatrixCOM;
//Bias Matrix in CoM representation
iDynTree::VectorDynSize BiasCOM;
//Gravity Matrix in CoM representation
iDynTree::MatrixDynSize GravMatrixCOM;
// Jacobian in CoM representation
iDynTree::MatrixDynSize JacCOM;
//Jacobian in CoM representation (only linear part)
iDynTree::MatrixDynSize JacCOM_lin;
// Bias acceleration J_dot*q_dot in CoM representation
iDynTree::MatrixDynSize JdqdCOM;
// Bias acceleration J_dot*q_dot in CoM representation
iDynTree::MatrixDynSize JdqdCOM_lin;
Eigen::VectorXd x_eigen;
Eigen::Matrix<double,3,1> fest;
Eigen::Matrix<double,18,1> Ctq;
Eigen::Matrix<double,18,18> Cm;
bool _first_wpose;
bool _first_jpos;
bool contact_br;
bool contact_bl;
bool contact_fl;
bool contact_fr;
bool flag_exit;
OPT *_o;
};
DOGCTRL::DOGCTRL() {
_o= new OPT(30,86,82);
_joint_state_sub = _nh.subscribe("/dogbot/joint_states", 1, &DOGCTRL::jointStateCallback, this);
_model_state_sub = _nh.subscribe("/gazebo/model_states", 1, &DOGCTRL::modelStateCallback, this);
_joint_pub = _nh.advertise<std_msgs::Float64MultiArray>("/dogbot/joint_position_controller/command", 1);
_model_name = "dogbot";
std::string path = ros::package::getPath("dogbot_description");
path += "/urdf/dogbot.urdf";
createrobot(path);
model = kinDynComp.model();
kinDynComp.setFrameVelocityRepresentation(iDynTree::MIXED_REPRESENTATION);
// Resize matrices of the class given the number of DOFs
n = model.getNrOfDOFs();
robot_mass = model.getTotalMass();
jointPos = iDynTree::VectorDynSize(n);
baseVel = iDynTree::Twist();
jointVel = iDynTree::VectorDynSize(n);
q = iDynTree::VectorDynSize(6+n);
dq = iDynTree::VectorDynSize(6+n);
qb = iDynTree::VectorDynSize(6+n);
dqb=iDynTree::VectorDynSize(6+n);
qmin= iDynTree::VectorDynSize(n);
qmax= iDynTree::VectorDynSize(n);
Bias=iDynTree::VectorDynSize(n+6);
GravMatrix=iDynTree::MatrixDynSize(n+6,1);
MassMatrix=iDynTree::FreeFloatingMassMatrix(model) ;
Jcom=iDynTree::MatrixDynSize(3,6+n);
Jac=iDynTree::MatrixDynSize(24,6+n);
JacDot=iDynTree::MatrixDynSize(24,6+n);
Jdqd=iDynTree::MatrixDynSize(24,1);
T=iDynTree::MatrixDynSize(6+n,6+n);
T_inv_dot=iDynTree::MatrixDynSize(6+n,6+n);
MassMatrixCOM=iDynTree::FreeFloatingMassMatrix(model) ;
BiasCOM=iDynTree::VectorDynSize(n+6);
GravMatrixCOM=iDynTree::MatrixDynSize(n+6,1);
JacCOM=iDynTree::MatrixDynSize(24,6+n);
JacCOM_lin=iDynTree::MatrixDynSize(12,6+n);
JdqdCOM=iDynTree::MatrixDynSize(24,1);
JdqdCOM_lin=iDynTree::MatrixDynSize(12,1);
x_eigen= Eigen::VectorXd::Zero(30);
_first_wpose = false;
_first_jpos = false;
contact_br= true;
contact_bl= true;
contact_bl= true;
contact_fr= true;
flag_exit=false;
}
void DOGCTRL::createrobot(std::string modelFile) {
if( !mdlLoader.loadModelFromFile(modelFile) ) {
std::cerr << "KinDynComputationsWithEigen: impossible to load model from " << modelFile << std::endl;
return ;
}
if( !kinDynComp.loadRobotModel(mdlLoader.model()) )
{
std::cerr << "KinDynComputationsWithEigen: impossible to load the following model in a KinDynComputations class:" << std::endl
<< mdlLoader.model().toString() << std::endl;
return ;
}
}
// Get joints position and velocity
void DOGCTRL::jointStateCallback(const sensor_msgs::JointState & msg) {
jstate_mutex.lock();
_jnt_pos(0,0)=msg.position[11];
_jnt_pos(1,0)=msg.position[8];
_jnt_pos(2,0)=msg.position[2];
_jnt_pos(3,0)=msg.position[5];
_jnt_pos(4,0)=msg.position[4];
_jnt_pos(5,0)=msg.position[3];
_jnt_pos(6,0)=msg.position[1];
_jnt_pos(7,0)=msg.position[0];
_jnt_pos(8,0)=msg.position[7];
_jnt_pos(9,0)=msg.position[6];
_jnt_pos(10,0)=msg.position[10];
_jnt_pos(11,0)=msg.position[9];
_jnt_vel(0,0)=msg.velocity[11];
_jnt_vel(1,0)=msg.velocity[8];
_jnt_vel(2,0)=msg.velocity[2];
_jnt_vel(3,0)=msg.velocity[5];
_jnt_vel(4,0)=msg.velocity[4];
_jnt_vel(5,0)=msg.velocity[3];
_jnt_vel(6,0)=msg.velocity[1];
_jnt_vel(7,0)=msg.velocity[0];
_jnt_vel(8,0)=msg.velocity[7];
_jnt_vel(9,0)=msg.velocity[6];
_jnt_vel(10,0)=msg.velocity[10];
_jnt_vel(11,0)=msg.velocity[9];
_first_jpos = true;
jstate_mutex.unlock();
}
// Get base position and velocity
void DOGCTRL::modelStateCallback(const gazebo_msgs::ModelStates & msg) {
wpos_mutex.lock();
bool found = false;
int index = 0;
while( !found && index < msg.name.size() ) {
if( msg.name[index] == _model_name )
found = true;
else index++;
}
if( found) {
_world_H_base.setIdentity();
//quaternion
tf::Quaternion q(msg.pose[index].orientation.x, msg.pose[index].orientation.y, msg.pose[index].orientation.z, msg.pose[index].orientation.w);
q.normalize();
Eigen::Matrix<double,3,3> rot;
tf::matrixTFToEigen(tf::Matrix3x3(q),rot);
//Roll, pitch, yaw
double roll, pitch, yaw;
tf::Matrix3x3(q).getRPY(roll, pitch, yaw);
//Set base pos (position and orientation)
_base_pos << msg.pose[index].position.x, msg.pose[index].position.y, msg.pose[index].position.z, roll, pitch, yaw;
//Set transformation matrix
_world_H_base.block(0,0,3,3)= rot;
_world_H_base.block(0,3,3,1)= _base_pos.block(0,0,3,1);
//Set base vel
_base_vel << msg.twist[index].linear.x, msg.twist[index].linear.y, msg.twist[index].linear.z, msg.twist[index].angular.x, msg.twist[index].angular.y, msg.twist[index].angular.z;
_first_wpose = true;
}
wpos_mutex.unlock();
}
// Compute matrix transformation T needed to recompute matrices/vector after the coordinate transform to the CoM
void DOGCTRL::computeTransformation(const Eigen::VectorXd &Vel_) {
//Set ausiliary matrices
iDynTree::MatrixDynSize Jb(6,6+n);
iDynTree::MatrixDynSize Jbc(3,n);
iDynTree::Vector3 xbc;
iDynTree::MatrixDynSize xbc_hat(3,3);
iDynTree::MatrixDynSize xbc_hat_dot(3,3);
iDynTree::MatrixDynSize Jbc_dot(6,6+n);
iDynTree::Vector3 xbo_dot;
//Set ausiliary matrices
iDynTree::Vector3 xbc_dot;
// Compute T matrix
// Get jacobians of the floating base and of the com
kinDynComp.getFrameFreeFloatingJacobian(0,Jb);
kinDynComp.getCenterOfMassJacobian(Jcom);
// Compute jacobian Jbc=d(xc-xb)/dq used in matrix T
toEigen(Jbc)<<toEigen(Jcom).block<3,12>(0,6)-toEigen(Jb).block<3,12>(0,6);
// Get xb (floating base position) and xc ( com position)
iDynTree::Position xb = world_H_base.getPosition();
iDynTree::Position xc= kinDynComp.getCenterOfMassPosition();
// Vector xcb=xc-xb
toEigen(xbc)=toEigen(xc)-toEigen(xb);
// Skew of xcb
toEigen(xbc_hat)<<0, -toEigen(xbc)[2], toEigen(xbc)[1],
toEigen(xbc)[2], 0, -toEigen(xbc)[0],
-toEigen(xbc)[1], toEigen(xbc)[0], 0;
Eigen::Matrix<double,6,6> X;
X<<Eigen::MatrixXd::Identity(3,3), toEigen(xbc_hat).transpose(),
Eigen::MatrixXd::Zero(3,3), Eigen::MatrixXd::Identity(3,3);
Eigen::MatrixXd Mb_Mj= toEigen(MassMatrix).block(0,0,6,6).bdcSvd(Eigen::ComputeThinU | Eigen::ComputeThinV).solve(toEigen(MassMatrix).block(0,6,6,12));
Eigen::Matrix<double,6,12> Js=X*Mb_Mj;
// Matrix T for the transformation
toEigen(T)<<Eigen::MatrixXd::Identity(3,3), toEigen(xbc_hat).transpose(), Js.block(0,0,3,12),
Eigen::MatrixXd::Zero(3,3), Eigen::MatrixXd::Identity(3,3), Js.block(3,0,3,12),
Eigen::MatrixXd::Zero(12,3), Eigen::MatrixXd::Zero(12,3), Eigen::MatrixXd::Identity(12,12);
//Compute time derivative of T
// Compute derivative of xbc
toEigen(xbc_dot)=toEigen(kinDynComp.getCenterOfMassVelocity())-toEigen(baseVel.getLinearVec3());
Eigen::VectorXd mdr=robot_mass*toEigen(xbc_dot);
Eigen::Matrix<double,3,3> mdr_hat;
mdr_hat<<0, -mdr[2], mdr[1],
mdr[2], 0, -mdr[0],
-mdr[1], mdr[0], 0;
//Compute skew of xbc
toEigen(xbc_hat_dot)<<0, -toEigen(xbc_dot)[2], toEigen(xbc_dot)[1],
toEigen(xbc_dot)[2], 0, -toEigen(xbc_dot)[0],
-toEigen(xbc_dot)[1], toEigen(xbc_dot)[0], 0;
Eigen::Matrix<double,6,6> dX;
dX<<Eigen::MatrixXd::Zero(3,3), toEigen(xbc_hat_dot).transpose(),
Eigen::MatrixXd::Zero(3,6);
// Time derivative of Jbc
kinDynComp.getCentroidalAverageVelocityJacobian(Jbc_dot);
Eigen::Matrix<double,6,6> dMb;
dMb<<Eigen::MatrixXd::Zero(3,3), mdr_hat.transpose(),
mdr_hat, Eigen::MatrixXd::Zero(3,3);
Eigen::MatrixXd inv_dMb1=(toEigen(MassMatrix).block(0,0,6,6).transpose().bdcSvd(Eigen::ComputeThinU | Eigen::ComputeThinV).solve(dMb.transpose())).transpose();
Eigen::MatrixXd inv_dMb2=-(toEigen(MassMatrix).block(0,0,6,6).bdcSvd(Eigen::ComputeThinU | Eigen::ComputeThinV).solve( inv_dMb1));
Eigen::Matrix<double,6,12> dJs=dX*Mb_Mj+X*inv_dMb2*toEigen(MassMatrix).block(0,6,6,12);
toEigen(T_inv_dot)<<Eigen::MatrixXd::Zero(3,3), toEigen(xbc_hat_dot), -dJs.block(0,0,3,12),
Eigen::MatrixXd::Zero(15,18);
}
//Update elements of the class given the new state
void DOGCTRL::update (Eigen::Matrix4d &eigenWorld_H_base, Eigen::Matrix<double,12,1> &eigenJointPos, Eigen::Matrix<double,12,1> &eigenJointVel, Eigen::Matrix<double,6,1> &eigenBasevel, Eigen::Vector3d &eigenGravity)
{
// Update joints, base and gravity from inputs
iDynTree::fromEigen(world_H_base,eigenWorld_H_base);
iDynTree::toEigen(jointPos) = eigenJointPos;
iDynTree::fromEigen(baseVel,eigenBasevel);
toEigen(jointVel) = eigenJointVel;
toEigen(gravity) = eigenGravity;
Eigen::Vector3d worldeigen=toEigen(world_H_base.getPosition());
cout<<"world update"<<world_H_base.getPosition().toString()<<endl;
while (worldeigen==Eigen::Vector3d::Zero()){
iDynTree::fromEigen(world_H_base,eigenWorld_H_base);
worldeigen=toEigen(world_H_base.getPosition());
}
//Set the state for the robot
kinDynComp.setRobotState(world_H_base,jointPos,
baseVel,jointVel,gravity);
// Compute Center of Mass
iDynTree::Vector3 base_angle=world_H_base.getRotation().asRPY();
toEigen(CoM)<<toEigen(kinDynComp.getCenterOfMassPosition()),
toEigen(base_angle);
cout << "World pos: " << eigenWorld_H_base << endl;
//cout << "Joint pos: " << eigenJointPos << endl;
cout << "CoMkinDynComp: " << toEigen(kinDynComp.getCenterOfMassPosition()) << endl;
cout << "CoM: " << toEigen(CoM).transpose() << endl;
//Compute velocity of the center of mass
toEigen(CoM_vel)<<toEigen(kinDynComp.getCenterOfMassVelocity()), eigenBasevel.block(3,0,3,1);
// Compute position base +joints
toEigen(qb)<<toEigen(world_H_base.getPosition()), toEigen(base_angle), eigenJointPos;
// Compute position COM+joints
toEigen(q)<<toEigen(CoM), eigenJointPos;
toEigen(dq)<<toEigen(CoM_vel), eigenJointVel;
toEigen(dqb) << eigenBasevel, eigenJointVel;
Eigen::MatrixXd qbd=toEigen(dqb);
Eigen::MatrixXd qdinv=qbd.completeOrthogonalDecomposition().pseudoInverse();
// Joint limits
toEigen(qmin)<<-1.75 , -1.75,-1.75,-1.75,-3.15, -0.02, -1.58, -2.62, -1.58, -2.62, -3.15, -0.02;
toEigen(qmax)<<1.75, 1.75, 1.75, 1.75, 1.58, 2.62, 3.15, 0.02, 3.15, 0.02, 1.58, 2.62;
// Get mass, bias (C(q,v)*v+g(q)) and gravity (g(q)) matrices
//Initialize ausiliary vector
iDynTree::FreeFloatingGeneralizedTorques bias_force(model);
iDynTree::FreeFloatingGeneralizedTorques grav_force(model);
//Compute Mass Matrix
kinDynComp.getFreeFloatingMassMatrix(MassMatrix);
//Compute Coriolis + gravitational terms (Bias)
kinDynComp.generalizedBiasForces(bias_force);
toEigen(Bias)<<iDynTree::toEigen(bias_force.baseWrench()),
iDynTree::toEigen(bias_force.jointTorques());
Eigen::MatrixXd Cmatrix=(toEigen(Bias)-toEigen(GravMatrix))*qdinv;
//Compute Gravitational term
kinDynComp.generalizedGravityForces(grav_force);
toEigen(GravMatrix)<<iDynTree::toEigen(grav_force.baseWrench()),
iDynTree::toEigen(grav_force.jointTorques());
computeJac();
// Compute Bias Acceleration -> J_dot*q_dot
computeJacDotQDot();
Eigen::Matrix<double, 18,1> q_dot;
q_dot<< eigenBasevel,
eigenJointVel;
// Compute Matrix needed for transformation from floating base representation to CoM representation
computeTransformation(q_dot);
// Compute Mass Matrix in CoM representation
toEigen(MassMatrixCOM)=toEigen(T).transpose().inverse()*toEigen(MassMatrix)*toEigen(T).inverse();
//cout << " MassMatrix: " << toEigen(MassMatrixCOM) << endl;
// Compute Coriolis+gravitational term in CoM representation
toEigen(BiasCOM)=toEigen(T).transpose().inverse()*toEigen(Bias)+toEigen(T).transpose().inverse()*toEigen(MassMatrix)*toEigen(T_inv_dot)*toEigen(dq);
Eigen::MatrixXd Ccom=toEigen(T).transpose().inverse()*Cmatrix*toEigen(T).inverse()+toEigen(T).transpose().inverse()*toEigen(MassMatrix)*toEigen(T_inv_dot);
Eigen::MatrixXd Biascom=Ccom*toEigen(dq);
Ctq=Ccom.transpose()*toEigen(dq);
// Compute gravitational term in CoM representation
Eigen::Matrix<double,18,1> go= Eigen::Matrix<double,18,1>::Zero();
go.block(0,0,3,1)<< 0,0,9.81;
toEigen(GravMatrixCOM)=toEigen(T).transpose().inverse()*toEigen(GravMatrix);
// Compute Jacobian term in CoM representation
toEigen(JacCOM)=toEigen(Jac)*toEigen(T).inverse();
ComputeJaclinear();
// Compute Bias Acceleration -> J_dot*q_dot in CoM representation
toEigen(JdqdCOM)=toEigen(Jdqd)+toEigen(Jac)*toEigen(T_inv_dot)*toEigen(dq);
computeJdqdCOMlinear();
}
// Compute Jacobian
void DOGCTRL::computeJac() {
//Set ausiliary matrices
iDynTree::MatrixDynSize Jac1(6,6+n);
iDynTree::MatrixDynSize Jac2(6,6+n);
iDynTree::MatrixDynSize Jac3(6,6+n);
iDynTree::MatrixDynSize Jac4(6,6+n);
// Compute Jacobian for each leg
// Jacobian for back right leg
kinDynComp.getFrameFreeFloatingJacobian(8,Jac1);
// Jacobian for back left leg
kinDynComp.getFrameFreeFloatingJacobian(11,Jac2);
// Jacobian for front left leg
kinDynComp.getFrameFreeFloatingJacobian(14,Jac3);
// Jacobian for front right leg
kinDynComp.getFrameFreeFloatingJacobian(17,Jac4);
// Full Jacobian
toEigen(Jac)<<toEigen(Jac1), toEigen(Jac2), toEigen(Jac3), toEigen(Jac4);
}
void DOGCTRL::ComputeJaclinear() {
Eigen::Matrix<double,12,24> B;
B<< Eigen::MatrixXd::Identity(3,3) , Eigen::MatrixXd::Zero(3,21),
Eigen::MatrixXd::Zero(3,6), Eigen::MatrixXd::Identity(3,3), Eigen::MatrixXd::Zero(3,15),
Eigen::MatrixXd::Zero(3,12), Eigen::MatrixXd::Identity(3,3), Eigen::MatrixXd::Zero(3,9),
Eigen::MatrixXd::Zero(3,18), Eigen::MatrixXd::Identity(3,3), Eigen::MatrixXd::Zero(3,3);
toEigen(JacCOM_lin)=B*toEigen(JacCOM);
}
void DOGCTRL::computeJdqdCOMlinear()
{
Eigen::Matrix<double,12,24> B;
B<< Eigen::MatrixXd::Identity(3,3) , Eigen::MatrixXd::Zero(3,21),
Eigen::MatrixXd::Zero(3,6), Eigen::MatrixXd::Identity(3,3), Eigen::MatrixXd::Zero(3,15),
Eigen::MatrixXd::Zero(3,12), Eigen::MatrixXd::Identity(3,3), Eigen::MatrixXd::Zero(3,9),
Eigen::MatrixXd::Zero(3,18), Eigen::MatrixXd::Identity(3,3), Eigen::MatrixXd::Zero(3,3);
toEigen(JdqdCOM_lin)= Eigen::MatrixXd::Zero(12,1);
toEigen(JdqdCOM_lin)=B*toEigen(JdqdCOM);
}
// Compute Bias acceleration: J_dot*q_dot
void DOGCTRL::computeJacDotQDot() {
// Bias acceleration for back right leg
iDynTree::Vector6 Jdqd1=kinDynComp.getFrameBiasAcc(8);
// Bias acceleration for back left leg
iDynTree::Vector6 Jdqd2=kinDynComp.getFrameBiasAcc(11);
// Bias acceleration for front left leg
iDynTree::Vector6 Jdqd3=kinDynComp.getFrameBiasAcc(14);
// Bias acceleration for front right leg
iDynTree::Vector6 Jdqd4=kinDynComp.getFrameBiasAcc(17);
toEigen(Jdqd)<<toEigen(Jdqd1), toEigen(Jdqd2), toEigen(Jdqd3), toEigen(Jdqd4);
}
void DOGCTRL::eebr_cb(gazebo_msgs::ContactsStateConstPtr eebr){
if(eebr->states.empty()){
contact_br= false;
}
else{
contact_br= true;
}
}
void DOGCTRL::eefl_cb(gazebo_msgs::ContactsStateConstPtr eefl){
if(eefl->states.empty()){
contact_fl= false;
}
else{
contact_fl= true;
}
}
void DOGCTRL::eebl_cb(gazebo_msgs::ContactsStateConstPtr eebl){
if(eebl->states.empty()){
contact_bl= false;
}
else{
contact_bl= true;
}
}
void DOGCTRL::eefr_cb(gazebo_msgs::ContactsStateConstPtr eefr){
if(eefr->states.empty()){
contact_fr= false;
}
else{
contact_fr= true;
}
}
void DOGCTRL::ctrl_loop() {
ros::ServiceClient pauseGazebo = _nh.serviceClient<std_srvs::Empty>("/gazebo/pause_physics");
ros::ServiceClient unpauseGazebo = _nh.serviceClient<std_srvs::Empty>("/gazebo/unpause_physics");
std_srvs::Empty pauseSrv;
_eebl_sub = _nh.subscribe("/dogbot/back_left_contactsensor_state",1, &DOGCTRL::eebl_cb, this);
_eefl_sub = _nh.subscribe("/dogbot/front_left_contactsensor_state",1, &DOGCTRL::eefl_cb, this);
_eebr_sub = _nh.subscribe("/dogbot/back_right_contactsensor_state",1, &DOGCTRL::eebr_cb, this);
_eefr_sub = _nh.subscribe("/dogbot/front_right_contactsensor_state",1,&DOGCTRL::eefr_cb, this);
//wait for first data...
while( !_first_wpose )
usleep(0.1*1e6);
while( !_first_jpos )
usleep(0.1*1e6);
//update
Eigen::Vector3d gravity;
gravity << 0, 0, -9.8;
update_mutex.lock();
update(_world_H_base, _jnt_pos, _jnt_vel, _base_vel, gravity);
update_mutex.unlock();
ros::Rate r(200);
Eigen::Matrix<double,6,1> CoMPosDes;
//CoMAccDes
std_msgs::Float64MultiArray tau1_msg;
ros::Time begin;
//feet
iDynTree::Transform World_bl;
Eigen::MatrixXd eeBLposM;
Eigen::Vector3d eeBLpos;
Eigen::MatrixXd eeFLposM;
Eigen::Vector3d eeFLpos;
Eigen::MatrixXd eeFRposM;
Eigen::Vector3d eeFRpos;
Eigen::MatrixXd eeBRposM;
Eigen::Vector3d eeBRpos;
while( ros::ok() ) {
towr::SplineHolder solution;
towr::SplineHolder solution2;
towr::NlpFormulation formulation;
towr::NlpFormulation formulation2;
Eigen::Matrix<double,6,1> delta_traj;
delta_traj<< 0, -0.07, 0, 0, 0, 0;
CoMPosDes << toEigen(CoM)[0], toEigen(CoM)[1]-0.07, 0.40299, 0, 0, toEigen(CoM)[5] ;
World_bl = kinDynComp.getWorldTransform(11);
eeBLposM = toEigen(World_bl.getPosition());
eeBLpos = eeBLposM.block(0,0,3,1);
cout << "Eeblpos " << eeBLpos << endl;
World_bl = kinDynComp.getWorldTransform(14);
eeFLposM = toEigen(World_bl.getPosition());
eeFLpos = eeFLposM.block(0,0,3,1);
cout << "Eeflpos " << eeFLpos << endl;
World_bl = kinDynComp.getWorldTransform(17);
eeFRposM = toEigen(World_bl.getPosition());
eeFRpos = eeFRposM.block(0,0,3,1);
cout << "Eefrpos " << eeFRpos << endl;
World_bl = kinDynComp.getWorldTransform(8);
eeBRposM = toEigen(World_bl.getPosition());
eeBRpos = eeBRposM.block(0,0,3,1);
cout << "Eebrpos " << eeBRpos << endl;
if(pauseGazebo.call(pauseSrv))
ROS_INFO("Simulation paused.");
else
ROS_INFO("Failed to pause simulation.");
get_trajectory( toEigen( CoM ), toEigen(CoM_vel), CoMPosDes, eeBLpos, eeBRpos, eeFLpos, eeFRpos, 1, 0.5, solution, formulation );
unpauseGazebo.call(pauseSrv);
begin=ros::Time::now();
while((ros::Time::now()-begin).toSec() < formulation.params_.ee_phase_durations_.at(1)[0] ) {
update_mutex.lock();
update(_world_H_base, _jnt_pos, _jnt_vel, _base_vel, gravity);
update_mutex.unlock();
// Taking Jacobian for CoM and joints
Eigen::Matrix<double, 12, 6> Jstcom= toEigen(JacCOM_lin).block(0,0,12,6);
Eigen::Matrix<double, 12, 12> Jstj= toEigen(JacCOM_lin).block(0,6,12,12);
Eigen::Matrix<double, 12, 18> Jst= toEigen(JacCOM_lin);
// cost function quadratic matrix
Eigen::Matrix<double,12,30> Sigma= Eigen::Matrix<double,12,30>::Zero();
Sigma.block(0,18,12,12)= Eigen::Matrix<double,12,12>::Identity();
Eigen::Matrix<double,6,30> T_s= Jstcom.transpose()*Sigma;
Eigen::Matrix<double,6,6> eigenQ1= 50*Eigen::Matrix<double,6,6>::Identity();
Eigen::Matrix<double,30,30> eigenQ2= T_s.transpose()*eigenQ1*T_s;
Eigen::Matrix<double,30,30> eigenR= Eigen::Matrix<double,30,30>::Identity();
Eigen::Matrix<double,30,30> eigenQ= eigenQ2+Eigen::Matrix<double,30,30>::Identity();
// Compute deltax, deltav
double t = (ros::Time::now()-begin).toSec();
Eigen::Matrix<double,6,1> CoMPosD;
CoMPosD << solution.base_linear_->GetPoint(t).p(), solution.base_angular_->GetPoint(t).p();
Eigen::Matrix<double,6,1> CoMVelD;
CoMVelD << solution.base_linear_->GetPoint(t).v(), solution.base_angular_->GetPoint(t).v();
Eigen::Matrix<double,6,1> CoMAccD;
CoMAccD << solution.base_linear_->GetPoint(t).a(), solution.base_angular_->GetPoint(t).a();
Eigen::Matrix<double,6,1> deltax = CoMPosD - toEigen( CoM );
cout << "Errore di posizione: " << deltax.transpose() << endl;
cout << "ComPosD: " << CoMPosD << endl;
cout << "CoM: " << toEigen( CoM ) << endl;
Eigen::Matrix<double,6,1> deltav = CoMVelD-toEigen(CoM_vel);
Eigen::MatrixXd g_acc = Eigen::MatrixXd::Zero(6,1);
g_acc(2,0)=9.81;
Eigen::MatrixXd M_com = toEigen(MassMatrixCOM).block(0,0,6,6);
Eigen::MatrixXd Kcom=3500*Eigen::MatrixXd::Identity(6,6);
Eigen::MatrixXd Dcom=50*Eigen::MatrixXd::Identity(6,6);
// Compute Desired vector
Eigen::Matrix<double,6,1> Wcom_des = Kcom*deltax+Dcom*deltav+robot_mass*g_acc+toEigen(MassMatrixCOM).block(0,0,6,6)*CoMAccD;
Eigen::Matrix<double,30,1> eigenc = -T_s.transpose()*eigenQ1.transpose()*Wcom_des;
_o->setQ( eigenQ );
_o->setc( eigenc );
//Equality constraints
Eigen::Matrix<double,18, 30> eigenA= Eigen::Matrix<double,18,30>::Zero();
eigenA.block(0,0,6,6)=toEigen(MassMatrixCOM).block(0,0,6,6);
eigenA.block(0,18,6,12)=-Jstcom.transpose();
eigenA.block(6,0,12,6)=Jstcom;
eigenA.block(6,6,12,12)=Jstj;
// Known term
Eigen::Matrix<double,18, 1> eigenb= Eigen::Matrix<double,18,1>::Zero();
eigenb.block(0,0,6,1)=-toEigen(BiasCOM).block(0,0,6,1);
eigenb.block(6,0,12,1)=-toEigen(JdqdCOM_lin);
//Inequality Constraints
Eigen::Matrix<double,68, 30> eigenD= Eigen::Matrix<double,68,30>::Zero();
// Torque limits
eigenD.block(20,6,12,12)=toEigen(MassMatrixCOM).block(6,6,12,12);
eigenD.block(20,18,12,12)=-Jstj.transpose();
eigenD.block(32,6,12,12)=-toEigen(MassMatrixCOM).block(6,6,12,12);
eigenD.block(32,18,12,12)=Jstj.transpose();
eigenD.block(44,6,12,12)=Eigen::Matrix<double,12,12>::Identity();
eigenD.block(56,6,12,12)=-Eigen::Matrix<double,12,12>::Identity();
//Friction
double mu=0.4;
Eigen::Matrix<double,3, 1> n= Eigen::Matrix<double,3,1>::Zero();
n<< 0, 0, 1;
Eigen::Matrix<double,3, 1> t1= Eigen::Matrix<double,3,1>::Zero();
t1<< 1, 0, 0;
Eigen::Matrix<double,3, 1> t2= Eigen::Matrix<double,3,1>::Zero();
t2<<0, 1, 0;
Eigen::Matrix<double,5,3> cfr=Eigen::Matrix<double,5,3>::Zero();
cfr<<(-mu*n+t1).transpose(),
(-mu*n+t2).transpose(),
-(mu*n+t1).transpose(),
-(mu*n+t2).transpose(),
-n.transpose();
Eigen::Matrix<double,20,12> Dfr=Eigen::Matrix<double,20,12>::Zero();
for(int i=0; i<4; i++)
{
Dfr.block(0+5*i,0+3*i,5,3)=cfr;
}
eigenD.block(0,18,20,12)=Dfr;
// Known terms for inequality
Eigen::Matrix<double,68, 1> eigenC= Eigen::Matrix<double,68,1>::Zero();
// Torque limits
Eigen::Matrix<double,12,1> tau_max=60*Eigen::Matrix<double,12,1>::Ones();
Eigen::Matrix<double,12,1> tau_min=-60*Eigen::Matrix<double,12,1>::Ones();
Eigen::Matrix<double,12, 1> eigenBiascom=toEigen(BiasCOM).block(6,0,12,1);
eigenC.block(20,0,12,1)=tau_max-eigenBiascom;
eigenC.block(32,0,12,1)=-(tau_min-eigenBiascom);
// Joints limits
double deltat=0.01;
Eigen::Matrix<double,12, 1> eigenq=toEigen(q).block(6,0,12,1);
Eigen::Matrix<double,12, 1> eigendq=toEigen(dq).block(6,0,12,1);
Eigen::Matrix<double,12, 1> eigenqmin=toEigen(qmin);
Eigen::Matrix<double,12, 1> eigenqmax=toEigen(qmax);
Eigen::Matrix<double,12, 1> ddqmin=(2/pow(deltat,2))*(eigenqmin-eigenq-deltat*eigendq);
Eigen::Matrix<double,12, 1> ddqmax=(2/pow(deltat,2))*(eigenqmax-eigenq-deltat*eigendq);
eigenC.block(44,0,12,1)=ddqmax;
eigenC.block(56,0,12,1)=-ddqmin;
Eigen::Matrix<double,18,18> Si;
Si<<Eigen::Matrix<double,6,18>::Zero(),
Eigen::Matrix<double,12,6>::Zero(),Eigen::Matrix<double,12,12>::Identity();
//Linear constraints matrix
Eigen::Matrix<double,86, 31> eigenL= Eigen::Matrix<double,86,31>::Zero();
eigenL<< eigenA,eigenb,
eigenD, eigenC;
_o->setL_stance( eigenL );
Eigen::VectorXd x_;
x_.resize( 30 );
_o->opt_stance( x_ );
Eigen::VectorXd tau= Eigen::VectorXd::Zero(12);
tau=toEigen(MassMatrixCOM).block(6,6,12,12)*x_.block(6,0,12,1)+eigenBiascom-Jstj.transpose()*x_.block(18,0,12,1);
//cout << "tau: " << tau.transpose() << endl;
tau1_msg.data.clear();
std::vector<double> ta(12,0.0);
// torques in right order
ta[11]=tau(7);
ta[10]=tau(6);
ta[9]=tau(2);
ta[8]=tau(5);
ta[7]=tau(4);
ta[6]=tau(3);
ta[5]=tau(9);
ta[4]=tau(8);
ta[3]=tau(1);
ta[2]=tau(11);
ta[1]=tau(10);
ta[0]=tau(0);
// Fill Command message
for(int i=0; i<12; i++) {
tau1_msg.data.push_back(ta[i]);
}
//Sending command
_joint_pub.publish(tau1_msg);
r.sleep();
}
flag_exit=false;
while((ros::Time::now()-begin).toSec() < formulation.params_.ee_phase_durations_.at(1)[1]+formulation.params_.ee_phase_durations_.at(1)[0] & flag_exit == false) {
update_mutex.lock();
update(_world_H_base, _jnt_pos, _jnt_vel, _base_vel, gravity);
update_mutex.unlock();
double duration= formulation.params_.ee_phase_durations_.at(1)[1]+formulation.params_.ee_phase_durations_.at(1)[0];
// Taking Jacobian for CoM and joints
int swl1, swl2, stl1, stl2;
swl1=0;
swl2=6 ;
stl1=3;
stl2=9 ;
Eigen::Matrix<double, 6, 18> Jst= Eigen::Matrix<double,6,18>::Zero();
Jst.block(0,0,3,18)=toEigen(JacCOM_lin).block(stl1,0,3,18);
Jst.block(3,0,3,18)=toEigen(JacCOM_lin).block(stl2,0,3,18);
Eigen::Matrix<double, 6, 18> Jsw= Eigen::Matrix<double,6,18>::Zero();