quadruped_ros2_control/commands/keyboard_input/src/KeyboardInput.cpp

120 lines
3.2 KiB
C++
Raw Normal View History

2024-09-11 11:32:54 +08:00
//
// Created by biao on 24-9-11.
//
#include <keyboard_input/KeyboardInput.h>
2024-09-11 20:41:12 +08:00
KeyboardInput::KeyboardInput() : Node("keyboard_input_node") {
2024-09-11 11:32:54 +08:00
publisher_ = create_publisher<control_input_msgs::msg::Inputs>("control_input", 10);
2024-09-11 20:41:12 +08:00
timer_ = create_wall_timer(std::chrono::microseconds(100), std::bind(&KeyboardInput::timer_callback, this));
2024-09-11 11:32:54 +08:00
inputs_ = control_input_msgs::msg::Inputs();
tcgetattr(STDIN_FILENO, &old_tio_);
new_tio_ = old_tio_;
new_tio_.c_lflag &= (~ICANON & ~ECHO);
tcsetattr(STDIN_FILENO, TCSANOW, &new_tio_);
RCLCPP_INFO(get_logger(), "Node initialized. Please input keys, press Ctrl+C to quit.");
}
2024-09-11 20:41:12 +08:00
void KeyboardInput::timer_callback() {
2024-09-11 11:32:54 +08:00
if (kbhit()) {
char key = getchar();
check_command(key);
2024-09-11 14:01:07 +08:00
if (inputs_.command == 0) check_value(key);
2024-09-11 11:32:54 +08:00
publisher_->publish(inputs_);
}
}
2024-09-11 20:41:12 +08:00
void KeyboardInput::check_command(const char key) {
2024-09-11 11:32:54 +08:00
switch (key) {
case '1':
inputs_.command = 1; // L2_B
break;
case '2':
inputs_.command = 2; // L2_A
break;
case '3':
inputs_.command = 3; // L2_X
break;
case '4':
inputs_.command = 4; // START
break;
case '0':
2024-09-11 14:01:07 +08:00
inputs_.command = 10; // L1_X
2024-09-11 11:32:54 +08:00
break;
case '9':
inputs_.command = 9; // L1_A
break;
case '8':
inputs_.command = 3; // L1_Y
break;
case ' ':
inputs_.lx = 0;
inputs_.ly = 0;
inputs_.rx = 0;
inputs_.ry = 0;
2024-09-11 14:01:07 +08:00
inputs_.command = 0;
2024-09-11 11:32:54 +08:00
break;
default:
2024-09-11 14:01:07 +08:00
inputs_.command = 0;
2024-09-11 11:32:54 +08:00
break;
}
}
2024-09-11 20:41:12 +08:00
void KeyboardInput::check_value(char key) {
2024-09-11 11:32:54 +08:00
switch (key) {
case 'w':
case 'W':
inputs_.ly = min<float>(inputs_.ly + sensitivity_left_, 1.0);
break;
case 's':
case 'S':
inputs_.ly = max<float>(inputs_.ly - sensitivity_left_, -1.0);
break;
case 'd':
case 'D':
inputs_.lx = min<float>(inputs_.lx + sensitivity_left_, 1.0);
break;
case 'a':
case 'A':
inputs_.lx = max<float>(inputs_.lx - sensitivity_left_, -1.0);
break;
case 'i':
case 'I':
inputs_.ry = min<float>(inputs_.ry + sensitivity_right_, 1.0);
break;
case 'k':
case 'K':
inputs_.ry = max<float>(inputs_.ry - sensitivity_right_, -1.0);
break;
case 'l':
case 'L':
inputs_.rx = min<float>(inputs_.rx + sensitivity_right_, 1.0);
break;
case 'j':
case 'J':
inputs_.rx = max<float>(inputs_.rx - sensitivity_right_, -1.0);
break;
default:
break;
}
}
2024-09-11 20:41:12 +08:00
bool KeyboardInput::kbhit() {
2024-09-11 11:32:54 +08:00
timeval tv = {0L, 0L};
fd_set fds;
FD_ZERO(&fds);
FD_SET(STDIN_FILENO, &fds);
return select(STDIN_FILENO + 1, &fds, NULL, NULL, &tv);
}
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
2024-09-11 20:41:12 +08:00
auto node = std::make_shared<KeyboardInput>();
2024-09-11 11:32:54 +08:00
spin(node);
rclcpp::shutdown();
return 0;
}