최대 1 분 소요

Intro

'teleop_twist_keyboard'는 ROS 패키지 중 하나로, 키보드를 사용하여 로봇을 제어하는 데 사용된다. 이번에는 해당 패키지를 공부하고 나만의 제어 패키지를 직접 구현해보도록 하겠다.

teleop_twist_keyboard 이란?

'teleop_twist_keyboard는' ROS 패키지 중 하나로, 키보드를 사용하여 로봇을 제어하는 데 사용된다. 이 패키지는 키보드로 입력된 명령을 통해 로봇을 움직이는 텔레오퍼레이션(teleoperation)을 가능하게 한다.

일반적으로 사용자는 터미널에서 teleop_twist_keyboard를 실행하고, 키보드를 사용하여 로봇을 전진, 후진, 회전 등의 동작을 수행할 수 있다. 이러한 입력은 키보드에서 받아들여진 명령을 ROS 메시지로 변환하고, 로봇 제어 노드에 전송하여 로봇을 움직이게 한다.

주요 기능은 다음과 같다:

  1. 키보드 입력을 통해 로봇을 제어.
  2. 명령을 로봇 제어 노드로 전송하여 로봇을 움직임.
  3. 키보드 입력에 따라 로봇의 선속도(linear velocity)와 각속도(angular velocity)를 조절.
  4. ROS의 시각화 도구를 통해 로봇의 현재 상태를 확인.

teleop_twist_keyboard는 간단하고 직관적인 방법으로 로봇을 제어할 수 있는 방법을 제공하며, ROS 개발 환경에서 로봇을 테스트하거나 디버깅하는 데 유용하다.

teleop_twist_keyboard_cpp

Cpp과 관련하여 오픈소스는 다음과 같다.

teleop_twist_keyboard.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
 
#include <stdio.h>
#include <unistd.h>
#include <termios.h>
 
#include <map>
 
// Map for movement keys
std::map<charstd::vector<float>> moveBindings
{
  {'i', {1000}},
  {'o', {100-1}},
  {'j', {0001}},
  {'l', {000-1}},
  {'u', {1001}},
  {',', {-1000}},
  {'.', {-1001}},
  {'m', {-100-1}},
  {'O', {1-100}},
  {'I', {1000}},
  {'J', {0100}},
  {'L', {0-100}},
  {'U', {1100}},
  {'<', {-1000}},
  {'>', {-1-100}},
  {'M', {-1100}},
  {'t', {0010}},
  {'b', {00-10}},
  {'k', {0000}},
  {'K', {0000}}
};
 
// Map for speed keys
std::map<charstd::vector<float>> speedBindings
{
  {'q', {1.11.1}},
  {'z', {0.90.9}},
  {'w', {1.11}},
  {'x', {0.91}},
  {'e', {11.1}},
  {'c', {10.9}}
};
 
// Reminder message
const char* msg = R"(
Reading from the keyboard and Publishing to Twist!
---------------------------
Moving around:
   u    i    o
   j    k    l
   m    ,    .
For Holonomic mode (strafing), hold down the shift key:
---------------------------
   U    I    O
   J    K    L
   M    <    >
t : up (+z)
b : down (-z)
anything else : stop
q/z : increase/decrease max speeds by 10%
w/x : increase/decrease only linear speed by 10%
e/c : increase/decrease only angular speed by 10%
CTRL-C to quit
)";
 
// Init variables
float speed(0.5); // Linear velocity (m/s)
float turn(1.0); // Angular velocity (rad/s)
float x(0), y(0), z(0), th(0); // Forward/backward/neutral direction vars
char key(' ');
 
// For non-blocking keyboard inputs
int getch(void)
{
  int ch;
  struct termios oldt;
  struct termios newt;
 
  // Store old settings, and copy to new settings
  tcgetattr(STDIN_FILENO, &oldt);
  newt = oldt;
 
  // Make required changes and apply the settings
  newt.c_lflag &= ~(ICANON | ECHO);
  newt.c_iflag |= IGNBRK;
  newt.c_iflag &= ~(INLCR | ICRNL | IXON | IXOFF);
  newt.c_lflag &= ~(ICANON | ECHO | ECHOK | ECHOE | ECHONL | ISIG | IEXTEN);
  newt.c_cc[VMIN] = 1;
  newt.c_cc[VTIME] = 0;
  tcsetattr(fileno(stdin), TCSANOW, &newt);
 
  // Get the current character
  ch = getchar();
 
  // Reapply old settings
  tcsetattr(STDIN_FILENO, TCSANOW, &oldt);
 
  return ch;
}
 
int main(int argc, char** argv)
{
  // Init ROS node
  ros::init(argc, argv, "teleop_twist_keyboard");
  ros::NodeHandle nh;
 
  // Init cmd_vel publisher
  ros::Publisher pub = nh.advertise<geometry_msgs::Twist>("cmd_vel"1);
 
  // Create Twist message
  geometry_msgs::Twist twist;
 
  printf("%s", msg);
  printf("\rCurrent: speed %f\tturn %f | Awaiting command...\r", speed, turn);
 
  while(true){
 
    // Get the pressed key
    key = getch();
 
    // If the key corresponds to a key in moveBindings
    if (moveBindings.count(key) == 1)
    {
      // Grab the direction data
      x = moveBindings[key][0];
      y = moveBindings[key][1];
      z = moveBindings[key][2];
      th = moveBindings[key][3];
 
      printf("\rCurrent: speed %f\tturn %f | Last command: %c   ", speed, turn, key);
    }
 
    // Otherwise if it corresponds to a key in speedBindings
    else if (speedBindings.count(key) == 1)
    {
      // Grab the speed data
      speed = speed * speedBindings[key][0];
      turn = turn * speedBindings[key][1];
 
      printf("\rCurrent: speed %f\tturn %f | Last command: %c   ", speed, turn, key);
    }
 
    // Otherwise, set the robot to stop
    else
    {
      x = 0;
      y = 0;
      z = 0;
      th = 0;
 
      // If ctrl-C (^C) was pressed, terminate the program
      if (key == '\x03')
      {
        printf("\n\n                 .     .\n              .  |\\-^-/|  .    \n             /| } O.=.O { |\\\n\n                 CH3EERS\n\n");
        break;
      }
 
      printf("\rCurrent: speed %f\tturn %f | Invalid command! %c", speed, turn, key);
    }
 
    // Update the Twist message
    twist.linear.x = x * speed;
    twist.linear.y = y * speed;
    twist.linear.z = z * speed;
 
    twist.angular.x = 0;
    twist.angular.y = 0;
    twist.angular.z = th * turn;
 
    // Publish it and resolve any remaining callbacks
    pub.publish(twist);
    ros::spinOnce();
  }
 
  return 0;
}
cs

Reference

태그: ,

카테고리:

업데이트: