moveit2
The MoveIt Motion Planning Framework for ROS 2.
servo_keyboard_input.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2023, PickNik LLC
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of PickNik LLC nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Title : servo_keyboard_input.cpp
36  * Project : moveit_servo
37  * Created : 05/31/2021
38  * Author : Adam Pettinger, V Mohammed Ibrahim
39  */
40 
41 #include <chrono>
42 #include <control_msgs/msg/joint_jog.hpp>
43 #include <geometry_msgs/msg/twist_stamped.hpp>
44 #include <moveit_msgs/srv/servo_command_type.hpp>
45 #include <rclcpp/rclcpp.hpp>
46 #include <signal.h>
47 #include <stdio.h>
48 #include <termios.h>
49 #include <unistd.h>
50 
51 // Define used keys
52 namespace
53 {
54 constexpr int8_t KEYCODE_RIGHT = 0x43;
55 constexpr int8_t KEYCODE_LEFT = 0x44;
56 constexpr int8_t KEYCODE_UP = 0x41;
57 constexpr int8_t KEYCODE_DOWN = 0x42;
58 constexpr int8_t KEYCODE_PERIOD = 0x2E;
59 constexpr int8_t KEYCODE_SEMICOLON = 0x3B;
60 constexpr int8_t KEYCODE_1 = 0x31;
61 constexpr int8_t KEYCODE_2 = 0x32;
62 constexpr int8_t KEYCODE_3 = 0x33;
63 constexpr int8_t KEYCODE_4 = 0x34;
64 constexpr int8_t KEYCODE_5 = 0x35;
65 constexpr int8_t KEYCODE_6 = 0x36;
66 constexpr int8_t KEYCODE_7 = 0x37;
67 constexpr int8_t KEYCODE_Q = 0x71;
68 constexpr int8_t KEYCODE_R = 0x72;
69 constexpr int8_t KEYCODE_J = 0x6A;
70 constexpr int8_t KEYCODE_T = 0x74;
71 constexpr int8_t KEYCODE_W = 0x77;
72 constexpr int8_t KEYCODE_E = 0x65;
73 } // namespace
74 
75 // Some constants used in the Servo Teleop demo
76 namespace
77 {
78 const std::string TWIST_TOPIC = "/servo_node/delta_twist_cmds";
79 const std::string JOINT_TOPIC = "/servo_node/delta_joint_cmds";
80 const size_t ROS_QUEUE_SIZE = 10;
81 const std::string PLANNING_FRAME_ID = "panda_link0";
82 const std::string EE_FRAME_ID = "panda_link8";
83 } // namespace
84 
85 // A class for reading the key inputs from the terminal
87 {
88 public:
89  KeyboardReader() : file_descriptor_(0)
90  {
91  // get the console in raw mode
92  tcgetattr(file_descriptor_, &cooked_);
93  struct termios raw;
94  memcpy(&raw, &cooked_, sizeof(struct termios));
95  raw.c_lflag &= ~(ICANON | ECHO);
96  // Setting a new line, then end of file
97  raw.c_cc[VEOL] = 1;
98  raw.c_cc[VEOF] = 2;
99  tcsetattr(file_descriptor_, TCSANOW, &raw);
100  }
101  void readOne(char* c)
102  {
103  int rc = read(file_descriptor_, c, 1);
104  if (rc < 0)
105  {
106  throw std::runtime_error("read failed");
107  }
108  }
109  void shutdown()
110  {
111  tcsetattr(file_descriptor_, TCSANOW, &cooked_);
112  }
113 
114 private:
115  int file_descriptor_;
116  struct termios cooked_;
117 };
118 
119 // Converts key-presses to Twist or Jog commands for Servo, in lieu of a controller
121 {
122 public:
123  KeyboardServo();
124  int keyLoop();
125 
126 private:
127  void spin();
128 
129  rclcpp::Node::SharedPtr nh_;
130 
131  rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr twist_pub_;
132  rclcpp::Publisher<control_msgs::msg::JointJog>::SharedPtr joint_pub_;
133  rclcpp::Client<moveit_msgs::srv::ServoCommandType>::SharedPtr switch_input_;
134 
135  std::shared_ptr<moveit_msgs::srv::ServoCommandType::Request> request_;
136  double joint_vel_cmd_;
137  std::string command_frame_id_;
138 };
139 
140 KeyboardServo::KeyboardServo() : joint_vel_cmd_(1.0), command_frame_id_{ "panda_link0" }
141 {
142  nh_ = rclcpp::Node::make_shared("servo_keyboard_input");
143 
144  twist_pub_ = nh_->create_publisher<geometry_msgs::msg::TwistStamped>(TWIST_TOPIC, ROS_QUEUE_SIZE);
145  joint_pub_ = nh_->create_publisher<control_msgs::msg::JointJog>(JOINT_TOPIC, ROS_QUEUE_SIZE);
146 
147  // Client for switching input types
148  switch_input_ = nh_->create_client<moveit_msgs::srv::ServoCommandType>("servo_node/switch_command_type");
149 }
150 
152 
153 void quit(int sig)
154 {
155  (void)sig;
156  input.shutdown();
157  rclcpp::shutdown();
158  exit(0);
159 }
160 
161 int main(int argc, char** argv)
162 {
163  rclcpp::init(argc, argv);
164  KeyboardServo keyboard_servo;
165 
166  signal(SIGINT, quit);
167 
168  int rc = keyboard_servo.keyLoop();
169  input.shutdown();
170  rclcpp::shutdown();
171 
172  return rc;
173 }
174 
175 void KeyboardServo::spin()
176 {
177  while (rclcpp::ok())
178  {
179  rclcpp::spin_some(nh_);
180  }
181 }
182 
184 {
185  char c;
186  bool publish_twist = false;
187  bool publish_joint = false;
188 
189  std::thread{ [this]() { return spin(); } }.detach();
190 
191  puts("Reading from keyboard");
192  puts("---------------------------");
193  puts("All commands are in the planning frame");
194  puts("Use arrow keys and the '.' and ';' keys to Cartesian jog");
195  puts("Use 1|2|3|4|5|6|7 keys to joint jog. 'r' to reverse the direction of jogging.");
196  puts("Use 'j' to select joint jog. ");
197  puts("Use 't' to select twist ");
198  puts("Use 'w' and 'e' to switch between sending command in planning frame or end effector frame");
199  puts("'Q' to quit.");
200 
201  for (;;)
202  {
203  // get the next event from the keyboard
204  try
205  {
206  input.readOne(&c);
207  }
208  catch (const std::runtime_error&)
209  {
210  perror("read():");
211  return -1;
212  }
213 
214  RCLCPP_DEBUG(nh_->get_logger(), "value: 0x%02X\n", c);
215 
216  // // Create the messages we might publish
217  auto twist_msg = std::make_unique<geometry_msgs::msg::TwistStamped>();
218  auto joint_msg = std::make_unique<control_msgs::msg::JointJog>();
219 
220  joint_msg->joint_names.resize(7);
221  joint_msg->joint_names = { "panda_joint1", "panda_joint2", "panda_joint3", "panda_joint4",
222  "panda_joint5", "panda_joint6", "panda_joint7" };
223 
224  joint_msg->velocities.resize(7);
225  std::fill(joint_msg->velocities.begin(), joint_msg->velocities.end(), 0.0);
226  // Use read key-press
227  switch (c)
228  {
229  case KEYCODE_LEFT:
230  RCLCPP_DEBUG(nh_->get_logger(), "LEFT");
231  twist_msg->twist.linear.y = -0.5;
232  publish_twist = true;
233  break;
234  case KEYCODE_RIGHT:
235  RCLCPP_DEBUG(nh_->get_logger(), "RIGHT");
236  twist_msg->twist.linear.y = 0.5;
237  publish_twist = true;
238  break;
239  case KEYCODE_UP:
240  RCLCPP_DEBUG(nh_->get_logger(), "UP");
241  twist_msg->twist.linear.x = 0.5;
242  publish_twist = true;
243  break;
244  case KEYCODE_DOWN:
245  RCLCPP_DEBUG(nh_->get_logger(), "DOWN");
246  twist_msg->twist.linear.x = -0.5;
247  publish_twist = true;
248  break;
249  case KEYCODE_PERIOD:
250  RCLCPP_DEBUG(nh_->get_logger(), "PERIOD");
251  twist_msg->twist.linear.z = -0.5;
252  publish_twist = true;
253  break;
254  case KEYCODE_SEMICOLON:
255  RCLCPP_DEBUG(nh_->get_logger(), "SEMICOLON");
256  twist_msg->twist.linear.z = 0.5;
257  publish_twist = true;
258  break;
259  case KEYCODE_1:
260  RCLCPP_DEBUG(nh_->get_logger(), "1");
261  joint_msg->velocities[0] = joint_vel_cmd_;
262  publish_joint = true;
263  break;
264  case KEYCODE_2:
265  RCLCPP_DEBUG(nh_->get_logger(), "2");
266  joint_msg->velocities[1] = joint_vel_cmd_;
267  publish_joint = true;
268  break;
269  case KEYCODE_3:
270  RCLCPP_DEBUG(nh_->get_logger(), "3");
271  joint_msg->velocities[2] = joint_vel_cmd_;
272  publish_joint = true;
273  break;
274  case KEYCODE_4:
275  RCLCPP_DEBUG(nh_->get_logger(), "4");
276  joint_msg->velocities[3] = joint_vel_cmd_;
277  publish_joint = true;
278  break;
279  case KEYCODE_5:
280  RCLCPP_DEBUG(nh_->get_logger(), "5");
281  joint_msg->velocities[4] = joint_vel_cmd_;
282  publish_joint = true;
283  break;
284  case KEYCODE_6:
285  RCLCPP_DEBUG(nh_->get_logger(), "6");
286  joint_msg->velocities[5] = joint_vel_cmd_;
287  publish_joint = true;
288  break;
289  case KEYCODE_7:
290  RCLCPP_DEBUG(nh_->get_logger(), "7");
291  joint_msg->velocities[6] = joint_vel_cmd_;
292  publish_joint = true;
293  break;
294  case KEYCODE_R:
295  RCLCPP_DEBUG(nh_->get_logger(), "r");
296  joint_vel_cmd_ *= -1;
297  break;
298  case KEYCODE_J:
299  RCLCPP_DEBUG(nh_->get_logger(), "j");
300  request_ = std::make_shared<moveit_msgs::srv::ServoCommandType::Request>();
301  request_->command_type = moveit_msgs::srv::ServoCommandType::Request::JOINT_JOG;
302  if (switch_input_->wait_for_service(std::chrono::seconds(1)))
303  {
304  auto result = switch_input_->async_send_request(request_);
305  if (result.get()->success)
306  {
307  RCLCPP_INFO_STREAM(nh_->get_logger(), "Switched to input type: JointJog");
308  }
309  else
310  {
311  RCLCPP_WARN_STREAM(nh_->get_logger(), "Could not switch input to: JointJog");
312  }
313  }
314  break;
315  case KEYCODE_T:
316  RCLCPP_DEBUG(nh_->get_logger(), "t");
317  request_ = std::make_shared<moveit_msgs::srv::ServoCommandType::Request>();
318  request_->command_type = moveit_msgs::srv::ServoCommandType::Request::TWIST;
319  if (switch_input_->wait_for_service(std::chrono::seconds(1)))
320  {
321  auto result = switch_input_->async_send_request(request_);
322  if (result.get()->success)
323  {
324  RCLCPP_INFO_STREAM(nh_->get_logger(), "Switched to input type: Twist");
325  }
326  else
327  {
328  RCLCPP_WARN_STREAM(nh_->get_logger(), "Could not switch input to: Twist");
329  }
330  }
331  break;
332  case KEYCODE_W:
333  RCLCPP_DEBUG(nh_->get_logger(), "w");
334  RCLCPP_INFO_STREAM(nh_->get_logger(), "Command frame set to: " << PLANNING_FRAME_ID);
335  command_frame_id_ = PLANNING_FRAME_ID;
336  break;
337  case KEYCODE_E:
338  RCLCPP_DEBUG(nh_->get_logger(), "e");
339  RCLCPP_INFO_STREAM(nh_->get_logger(), "Command frame set to: " << EE_FRAME_ID);
340  command_frame_id_ = EE_FRAME_ID;
341  break;
342  case KEYCODE_Q:
343  RCLCPP_DEBUG(nh_->get_logger(), "quit");
344  return 0;
345  }
346 
347  // If a key requiring a publish was pressed, publish the message now
348  if (publish_twist)
349  {
350  twist_msg->header.stamp = nh_->now();
351  twist_msg->header.frame_id = command_frame_id_;
352  twist_pub_->publish(std::move(twist_msg));
353  publish_twist = false;
354  }
355  else if (publish_joint)
356  {
357  joint_msg->header.stamp = nh_->now();
358  joint_msg->header.frame_id = PLANNING_FRAME_ID;
359  joint_pub_->publish(std::move(joint_msg));
360  publish_joint = false;
361  }
362  }
363 
364  return 0;
365 }
int main(int argc, char **argv)
KeyboardReader input
void quit(int sig)