// // Created by biao on 24-9-10. // #include #include #include StateFixedStand::StateFixedStand(CtrlComponent ctrlComp): FSMState( FSMStateName::FIXEDSTAND, "fixed stand", std::move(ctrlComp)) { } void StateFixedStand::enter() { for (int i = 0; i < 12; i++) { start_pos_[i] = ctrlComp_.joint_position_state_interface_[i].get().get_value(); } } void StateFixedStand::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); 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() { percent_ = 0; } FSMStateName StateFixedStand::checkChange() { if (percent_ < 1) { return FSMStateName::FIXEDSTAND; } if (ctrlComp_.control_inputs_.get().command == 1) { return FSMStateName::FIXEDDOWN; } return FSMStateName::FIXEDSTAND; }