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

49 lines
1.4 KiB
C++
Raw Normal View History

2024-09-11 20:41:12 +08:00
//
// Created by tlab-uav on 24-9-11.
//
#include <cmath>
#include <unitree_guide_controller/FSM/StateFixedDown.h>
StateFixedDown::StateFixedDown(CtrlComponent ctrlComp): FSMState(
FSMStateName::FIXEDDOWN, "fixed down", std::move(ctrlComp)) {
// duration_ = ctrlComp_.frequency_ * 15;
}
void StateFixedDown::enter() {
for (int i = 0; i < 12; i++) {
start_pos_[i] = ctrlComp_.joint_position_state_interface_[i].get().get_value();
}
}
void StateFixedDown::run() {
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);
2024-09-12 20:04:20 +08:00
ctrlComp_.joint_kp_command_interface_[i].get().set_value(50.0);
2024-09-11 20:41:12 +08:00
ctrlComp_.joint_kd_command_interface_[i].get().set_value(3.5);
}
}
void StateFixedDown::exit() {
percent_ = 0;
}
FSMStateName StateFixedDown::checkChange() {
2024-09-12 20:04:20 +08:00
if (percent_ < 2) {
2024-09-11 20:41:12 +08:00
return FSMStateName::FIXEDDOWN;
}
switch (ctrlComp_.control_inputs_.get().command) {
case 1:
return FSMStateName::PASSIVE;
case 2:
return FSMStateName::FIXEDSTAND;
default:
return FSMStateName::FIXEDDOWN;
}
}