z1_sdk/examples/bigDemo.cpp

177 lines
5.0 KiB
C++
Raw Normal View History

2022-11-11 18:17:07 +08:00
#include "control/unitreeArm.h"
2022-09-13 19:52:44 +08:00
class Z1ARM : public unitreeArm{
2022-09-13 19:52:44 +08:00
public:
2022-11-11 18:17:07 +08:00
Z1ARM(CtrlComponents * ctrlComp):unitreeArm(ctrlComp){};
~Z1ARM(){};
2022-09-13 19:52:44 +08:00
void armCtrlByFSM();
void armCtrlByTraj();
void armCtrlTrackInJointCtrl();
void armCtrlTrackInCartesian();
2022-11-11 18:17:07 +08:00
void printState();
2022-09-13 19:52:44 +08:00
};
void Z1ARM::armCtrlByFSM() {
2022-09-13 19:52:44 +08:00
Vec6 posture[2];
std::cout << "[JOINTCTRL]" << std::endl;
setFsm(ArmFSMState::JOINTCTRL);
2022-11-11 18:17:07 +08:00
std::cout << "[TO STATE]" << std::endl;
2022-09-13 19:52:44 +08:00
labelRun("forward");
2022-11-11 18:17:07 +08:00
2022-09-13 19:52:44 +08:00
std::cout << "[MOVEJ]" << std::endl;
posture[0]<<0.5,0.1,0.1,0.5,-0.2,0.5;
2022-11-11 18:17:07 +08:00
MoveJ(posture[0], -M_PI/3.0, 1.0);
2022-09-13 19:52:44 +08:00
std::cout << "[MOVEL]" << std::endl;
posture[0] << 0,0,0,0.45,-0.2,0.2;
2022-11-11 18:17:07 +08:00
MoveL(posture[0], 0., 0.3);
2022-09-13 19:52:44 +08:00
std::cout << "[MOVEC]" << std::endl;
2022-11-11 18:17:07 +08:00
posture[0] << 0,0,0,0.45,0,0.4;
2022-09-13 19:52:44 +08:00
posture[1] << 0,0,0,0.45,0.2,0.2;
2022-11-11 18:17:07 +08:00
MoveC(posture[0], posture[1], -M_PI/3.0, 0.3);
2022-09-13 19:52:44 +08:00
}
void Z1ARM::armCtrlByTraj(){
2022-09-13 19:52:44 +08:00
Vec6 posture[2];
2022-11-11 18:17:07 +08:00
int order = 1;
2022-09-13 19:52:44 +08:00
labelRun("forward");
2022-11-11 18:17:07 +08:00
_trajCmd.trajOrder = 0;//if order == 0, clear traj
setTraj();
2022-09-13 19:52:44 +08:00
// No.1 trajectory
_trajCmd.trajOrder = order++;
_trajCmd.trajType = TrajType::MoveJ;
2022-11-11 18:17:07 +08:00
_trajCmd.maxSpeed = 1.0;// angular velocity, rad/s
_trajCmd.gripperPos = 0.0;
2022-09-13 19:52:44 +08:00
posture[0] << 0.5,0.1,0.1,0.5,-0.2,0.5;
_trajCmd.posture[0] = Vec6toPosture(posture[0]);
2022-11-11 18:17:07 +08:00
setTraj();
2022-09-13 19:52:44 +08:00
// No.2 trajectory
_trajCmd.trajOrder = order++;
_trajCmd.trajType = TrajType::Stop;
_trajCmd.stopTime = 1.0;
_trajCmd.gripperPos = -1.0;
2022-11-11 18:17:07 +08:00
setTraj();
// No.3 trajectory
_trajCmd.trajOrder = order++;
2022-09-13 19:52:44 +08:00
_trajCmd.trajType = TrajType::MoveL;
2022-11-11 18:17:07 +08:00
_trajCmd.maxSpeed = 0.3; // Cartesian velocity , m/s
2022-09-13 19:52:44 +08:00
_trajCmd.gripperPos = 0.0;
posture[0] << 0,0,0,0.45,-0.2,0.2;
_trajCmd.posture[0] = Vec6toPosture(posture[0]);
2022-11-11 18:17:07 +08:00
setTraj();
2022-09-13 19:52:44 +08:00
// No.4 trajectory
_trajCmd.trajOrder = order++;
_trajCmd.trajType = TrajType::Stop;
_trajCmd.stopTime = 1.0;
_trajCmd.gripperPos = -1.0;
2022-11-11 18:17:07 +08:00
setTraj();
2022-09-13 19:52:44 +08:00
// No.5 trajectory
2022-09-13 19:52:44 +08:00
_trajCmd.trajOrder = order++;
_trajCmd.trajType = TrajType::MoveC;
_trajCmd.maxSpeed = 0.3; // Cartesian velocity
_trajCmd.gripperPos = 0.0;
2022-09-13 19:52:44 +08:00
posture[0] << 0,0,0,0.45,0,0.4;
posture[1] << 0,0,0,0.45,0.2,0.2;
_trajCmd.posture[0] = Vec6toPosture(posture[0]);
_trajCmd.posture[1] = Vec6toPosture(posture[1]);
2022-11-11 18:17:07 +08:00
setTraj();
2022-09-13 19:52:44 +08:00
2022-11-11 18:17:07 +08:00
startTraj();
// wait for trajectory completion
2022-11-11 18:17:07 +08:00
while (_ctrlComp->recvState.state != ArmFSMState::JOINTCTRL){
usleep(_ctrlComp->dt*1000000);
2022-09-13 19:52:44 +08:00
}
}
void Z1ARM::armCtrlTrackInJointCtrl(){
2022-11-11 18:17:07 +08:00
labelRun("forward");
startTrack(ArmFSMState::JOINTCTRL);
for(;;){
2022-11-11 18:17:07 +08:00
q(3) -= _ctrlComp->dt * 1.0;//max dt*PI, rad/s
2022-09-13 19:52:44 +08:00
2022-11-11 18:17:07 +08:00
qPast = _ctrlComp->lowstate->getQ();
// std::cout << "qCmd: " << q.transpose() << " qState: " << qPast.transpose() << std::endl;
//The joint has reached limit, there is warning: joint cmd is far from state
2022-11-11 18:17:07 +08:00
double error = fabs(q(3) - qPast(3));
if(error > 0.1){
break;
}
2022-11-11 18:17:07 +08:00
usleep(_ctrlComp->dt*1000000);
}
2022-11-11 18:17:07 +08:00
_ctrlComp->sendCmd.track = false;
}
2022-09-13 19:52:44 +08:00
void Z1ARM::armCtrlTrackInCartesian(){
labelRun("forward");
2022-11-11 18:17:07 +08:00
startTrack(ArmFSMState::CARTESIAN);
for(;;){
2022-11-11 18:17:07 +08:00
_ctrlComp->lowcmd->endPosture(5) -= _ctrlComp->dt * 0.2;//z, m/s
// no inverse kinematics solution, the joint has reached limit
2022-11-11 18:17:07 +08:00
// std::cout << "postureCmd: " << _ctrlComp->lowcmd->endPosture.transpose() << " qState: " << _ctrlComp->lowstate->endPosture.transpose() << std::endl;
double error = fabs(_ctrlComp->lowcmd->endPosture(5) - _ctrlComp->lowstate->endPosture(5));
if( error > 0.1){
break;
}
2022-11-11 18:17:07 +08:00
usleep(_ctrlComp->dt*1000000);
2022-09-13 19:52:44 +08:00
}
2022-11-11 18:17:07 +08:00
_ctrlComp->sendCmd.track = false;
}
void Z1ARM::printState(){
std::cout<<"------ joint State ------"<<std::endl;
std::cout<<"qState: "<<_ctrlComp->lowstate->getQ().transpose()<<std::endl;
std::cout<<"qdState: "<<_ctrlComp->lowstate->getQd().transpose()<<std::endl;
std::cout<<"tauState: "<<_ctrlComp->lowstate->getTau().transpose()<<std::endl;
std::cout<<"------ Endeffector Cartesian Posture ------"<<std::endl;
std::cout<<"roll pitch yaw x y z"<<std::endl;
std::cout<<_ctrlComp->lowstate->endPosture.transpose()<<std::endl;
}
2022-09-13 19:52:44 +08:00
int main() {
2022-11-11 18:17:07 +08:00
CtrlComponents *ctrlComp = new CtrlComponents(0.002);
Z1ARM arm(ctrlComp);
arm.sendRecvThread->start();
arm.backToStart();
2022-11-11 18:17:07 +08:00
// size_t demo = 2;
for(size_t demo = 1; demo < 5; demo++)
// for(;;)
2022-11-11 18:17:07 +08:00
switch (demo)
{
case 1:
arm.armCtrlByFSM();
break;
case 2:
arm.armCtrlByTraj();
break;
case 3:
arm.armCtrlTrackInJointCtrl();
break;
case 4:
arm.armCtrlTrackInCartesian();
break;
default:
break;
}
arm.backToStart();
2022-11-11 18:17:07 +08:00
arm.setFsm(ArmFSMState::PASSIVE);
arm.sendRecvThread->shutdown();
delete ctrlComp;
2022-09-13 19:52:44 +08:00
return 0;
}