quadruped_ros2_control/controllers/unitree_guide_controller/src/FSM/StateFixedStand.cpp

46 lines
1.3 KiB
C++
Raw Normal View History

//
// Created by biao on 24-9-10.
//
2024-09-11 20:41:12 +08:00
#include <cmath>
#include <iostream>
#include <unitree_guide_controller/FSM/StateFixedStand.h>
StateFixedStand::StateFixedStand(CtrlComponent ctrlComp): FSMState(
FSMStateName::FIXEDSTAND, "fixed stand", std::move(ctrlComp)) {
}
void StateFixedStand::enter() {
2024-09-11 14:01:07 +08:00
for (int i = 0; i < 12; i++) {
2024-09-11 20:41:12 +08:00
start_pos_[i] = ctrlComp_.joint_position_state_interface_[i].get().get_value();
2024-09-11 14:01:07 +08:00
}
}
void StateFixedStand::run() {
2024-09-11 20:41:12 +08:00
percent_ += 1 / duration_;
phase = std::tanh(percent_);
for (int i = 0; i < 12; i++) {
ctrlComp_.joint_position_command_interface_[i].get().set_value(
phase * target_pos_[i] + (1 - phase) * start_pos_[i]);
ctrlComp_.joint_velocity_command_interface_[i].get().set_value(0);
ctrlComp_.joint_effort_command_interface_[i].get().set_value(0);
ctrlComp_.joint_kp_command_interface_[i].get().set_value(
phase * 50.0 + (1 - phase) * 20.0);
ctrlComp_.joint_kd_command_interface_[i].get().set_value(8);
}
}
void StateFixedStand::exit() {
2024-09-11 20:41:12 +08:00
percent_ = 0;
}
FSMStateName StateFixedStand::checkChange() {
2024-09-11 20:41:12 +08:00
if (percent_ < 1) {
return FSMStateName::FIXEDSTAND;
}
2024-09-11 14:01:07 +08:00
if (ctrlComp_.control_inputs_.get().command == 1) {
2024-09-11 20:41:12 +08:00
return FSMStateName::FIXEDDOWN;
2024-09-11 14:01:07 +08:00
}
return FSMStateName::FIXEDSTAND;
}