2024-09-16 21:15:34 +08:00
|
|
|
//
|
|
|
|
// Created by tlab-uav on 24-9-16.
|
|
|
|
//
|
|
|
|
|
|
|
|
#include "unitree_guide_controller/FSM/StateBalanceTest.h"
|
|
|
|
|
|
|
|
#include <unitree_guide_controller/common/mathTools.h>
|
|
|
|
|
|
|
|
StateBalanceTest::StateBalanceTest(CtrlComponent ctrlComp) : FSMState(FSMStateName::BALANCETEST, "balance test",
|
|
|
|
std::move(ctrlComp)) {
|
|
|
|
_xMax = 0.05;
|
|
|
|
_xMin = -_xMax;
|
|
|
|
_yMax = 0.05;
|
|
|
|
_yMin = -_yMax;
|
|
|
|
_zMax = 0.04;
|
|
|
|
_zMin = -_zMax;
|
|
|
|
_yawMax = 20 * M_PI / 180;
|
|
|
|
_yawMin = -_yawMax;
|
|
|
|
|
|
|
|
Kp_p_ = Vec3(150, 150, 150).asDiagonal();
|
|
|
|
Kd_p_ = Vec3(25, 25, 25).asDiagonal();
|
|
|
|
|
|
|
|
kp_w_ = 200;
|
|
|
|
Kd_w_ = Vec3(30, 30, 30).asDiagonal();
|
|
|
|
}
|
|
|
|
|
|
|
|
void StateBalanceTest::enter() {
|
2024-09-17 18:21:04 +08:00
|
|
|
pcdInit_ = ctrl_comp_.estimator_.get().getPosition();
|
|
|
|
pcd_ = pcdInit_;
|
2024-09-17 19:42:21 +08:00
|
|
|
init_rotation_ = ctrl_comp_.estimator_.get().getRotation();
|
2024-09-16 21:15:34 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
void StateBalanceTest::run() {
|
2024-09-17 14:03:08 +08:00
|
|
|
pcd_(0) = pcdInit_(0) + invNormalize(ctrl_comp_.control_inputs_.get().ly, _xMin, _xMax);
|
|
|
|
pcd_(1) = pcdInit_(1) - invNormalize(ctrl_comp_.control_inputs_.get().lx, _yMin, _yMax);
|
|
|
|
pcd_(2) = pcdInit_(2) + invNormalize(ctrl_comp_.control_inputs_.get().ry, _zMin, _zMax);
|
|
|
|
const float yaw = invNormalize(ctrl_comp_.control_inputs_.get().rx, _yawMin, _yawMax);
|
2024-09-17 19:42:21 +08:00
|
|
|
Rd_ = Mat3((KDL::Rotation::RPY(0, 0, yaw).Inverse() * init_rotation_).data);
|
2024-09-16 21:15:34 +08:00
|
|
|
|
2024-09-17 14:03:08 +08:00
|
|
|
pose_body_ = ctrl_comp_.estimator_.get().getPosition();
|
|
|
|
vel_body_ = ctrl_comp_.estimator_.get().getVelocity();
|
2024-09-16 21:15:34 +08:00
|
|
|
|
|
|
|
for (int i = 0; i < 12; i++) {
|
2024-09-17 14:03:08 +08:00
|
|
|
ctrl_comp_.joint_kp_command_interface_[i].get().set_value(0.8);
|
|
|
|
ctrl_comp_.joint_kd_command_interface_[i].get().set_value(0.8);
|
2024-09-16 21:15:34 +08:00
|
|
|
}
|
2024-09-17 14:03:08 +08:00
|
|
|
|
|
|
|
calcTorque();
|
2024-09-16 21:15:34 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
void StateBalanceTest::exit() {
|
|
|
|
}
|
|
|
|
|
|
|
|
FSMStateName StateBalanceTest::checkChange() {
|
2024-09-17 14:03:08 +08:00
|
|
|
switch (ctrl_comp_.control_inputs_.get().command) {
|
2024-09-16 21:15:34 +08:00
|
|
|
case 1:
|
|
|
|
return FSMStateName::FIXEDDOWN;
|
|
|
|
case 2:
|
|
|
|
return FSMStateName::FIXEDSTAND;
|
|
|
|
default:
|
|
|
|
return FSMStateName::BALANCETEST;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void StateBalanceTest::calcTorque() {
|
2024-09-17 18:21:04 +08:00
|
|
|
const auto B2G_Rotation = Eigen::Matrix3d(ctrl_comp_.estimator_.get().getRotation().data);
|
|
|
|
const RotMat G2B_Rotation = B2G_Rotation.transpose();
|
|
|
|
|
2024-09-16 21:15:34 +08:00
|
|
|
// expected body acceleration
|
2024-09-17 18:21:04 +08:00
|
|
|
dd_pcd_ = Kp_p_ * Vec3((pcd_ - pose_body_).data) + Kd_p_ * Vec3((-vel_body_).data);
|
2024-09-16 21:15:34 +08:00
|
|
|
|
|
|
|
// expected body angular acceleration
|
2024-09-17 18:21:04 +08:00
|
|
|
d_wbd_ = kp_w_ * rotMatToExp(Rd_ * G2B_Rotation) +
|
2024-09-17 19:42:21 +08:00
|
|
|
Kd_w_ * (Vec3(0, 0, 0) - Vec3((-ctrl_comp_.estimator_.get().getGlobalGyro()).data));
|
2024-09-16 21:15:34 +08:00
|
|
|
|
|
|
|
// calculate foot force
|
|
|
|
const std::vector contact(4, 1);
|
2024-09-17 18:21:04 +08:00
|
|
|
const Vec34 foot_force = G2B_Rotation * ctrl_comp_.balance_ctrl_.get().calF(dd_pcd_, -d_wbd_, B2G_Rotation,
|
|
|
|
ctrl_comp_.estimator_.get().
|
|
|
|
getFootPos2Body(), contact);
|
2024-09-16 21:15:34 +08:00
|
|
|
|
2024-09-17 14:03:08 +08:00
|
|
|
std::vector<KDL::JntArray> current_joints = ctrl_comp_.robot_model_.get().current_joint_pos_;
|
2024-09-16 21:15:34 +08:00
|
|
|
for (int i = 0; i < 4; i++) {
|
2024-09-17 18:21:04 +08:00
|
|
|
KDL::JntArray torque = ctrl_comp_.robot_model_.get().getTorque(-foot_force.col(i), i);
|
2024-09-16 21:15:34 +08:00
|
|
|
for (int j = 0; j < 3; j++) {
|
2024-09-17 14:03:08 +08:00
|
|
|
ctrl_comp_.joint_effort_command_interface_[i * 3 + j].get().set_value(torque(j));
|
|
|
|
ctrl_comp_.joint_position_command_interface_[i * 3 + j].get().set_value(current_joints[i](j));
|
2024-09-16 21:15:34 +08:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|