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>
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;
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";
92 tcgetattr(file_descriptor_, &cooked_);
94 memcpy(&raw, &cooked_,
sizeof(
struct termios));
95 raw.c_lflag &= ~(ICANON | ECHO);
99 tcsetattr(file_descriptor_, TCSANOW, &raw);
103 int rc = read(file_descriptor_, c, 1);
106 throw std::runtime_error(
"read failed");
111 tcsetattr(file_descriptor_, TCSANOW, &cooked_);
115 int file_descriptor_;
116 struct termios cooked_;
129 rclcpp::Node::SharedPtr nh_;
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_;
135 std::shared_ptr<moveit_msgs::srv::ServoCommandType::Request> request_;
136 double joint_vel_cmd_;
137 std::string command_frame_id_;
142 nh_ = rclcpp::Node::make_shared(
"servo_keyboard_input");
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);
148 switch_input_ = nh_->create_client<moveit_msgs::srv::ServoCommandType>(
"servo_node/switch_command_type");
161 int main(
int argc,
char** argv)
163 rclcpp::init(argc, argv);
166 signal(SIGINT,
quit);
168 int rc = keyboard_servo.
keyLoop();
175 void KeyboardServo::spin()
179 rclcpp::spin_some(nh_);
186 bool publish_twist =
false;
187 bool publish_joint =
false;
189 std::thread{ [
this]() {
return spin(); } }.detach();
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.");
208 catch (
const std::runtime_error&)
214 RCLCPP_DEBUG(nh_->get_logger(),
"value: 0x%02X\n", c);
217 auto twist_msg = std::make_unique<geometry_msgs::msg::TwistStamped>();
218 auto joint_msg = std::make_unique<control_msgs::msg::JointJog>();
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" };
224 joint_msg->velocities.resize(7);
225 std::fill(joint_msg->velocities.begin(), joint_msg->velocities.end(), 0.0);
230 RCLCPP_DEBUG(nh_->get_logger(),
"LEFT");
231 twist_msg->twist.linear.y = -0.5;
232 publish_twist =
true;
235 RCLCPP_DEBUG(nh_->get_logger(),
"RIGHT");
236 twist_msg->twist.linear.y = 0.5;
237 publish_twist =
true;
240 RCLCPP_DEBUG(nh_->get_logger(),
"UP");
241 twist_msg->twist.linear.x = 0.5;
242 publish_twist =
true;
245 RCLCPP_DEBUG(nh_->get_logger(),
"DOWN");
246 twist_msg->twist.linear.x = -0.5;
247 publish_twist =
true;
250 RCLCPP_DEBUG(nh_->get_logger(),
"PERIOD");
251 twist_msg->twist.linear.z = -0.5;
252 publish_twist =
true;
254 case KEYCODE_SEMICOLON:
255 RCLCPP_DEBUG(nh_->get_logger(),
"SEMICOLON");
256 twist_msg->twist.linear.z = 0.5;
257 publish_twist =
true;
260 RCLCPP_DEBUG(nh_->get_logger(),
"1");
261 joint_msg->velocities[0] = joint_vel_cmd_;
262 publish_joint =
true;
265 RCLCPP_DEBUG(nh_->get_logger(),
"2");
266 joint_msg->velocities[1] = joint_vel_cmd_;
267 publish_joint =
true;
270 RCLCPP_DEBUG(nh_->get_logger(),
"3");
271 joint_msg->velocities[2] = joint_vel_cmd_;
272 publish_joint =
true;
275 RCLCPP_DEBUG(nh_->get_logger(),
"4");
276 joint_msg->velocities[3] = joint_vel_cmd_;
277 publish_joint =
true;
280 RCLCPP_DEBUG(nh_->get_logger(),
"5");
281 joint_msg->velocities[4] = joint_vel_cmd_;
282 publish_joint =
true;
285 RCLCPP_DEBUG(nh_->get_logger(),
"6");
286 joint_msg->velocities[5] = joint_vel_cmd_;
287 publish_joint =
true;
290 RCLCPP_DEBUG(nh_->get_logger(),
"7");
291 joint_msg->velocities[6] = joint_vel_cmd_;
292 publish_joint =
true;
295 RCLCPP_DEBUG(nh_->get_logger(),
"r");
296 joint_vel_cmd_ *= -1;
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)))
304 auto result = switch_input_->async_send_request(request_);
305 if (result.get()->success)
307 RCLCPP_INFO_STREAM(nh_->get_logger(),
"Switched to input type: JointJog");
311 RCLCPP_WARN_STREAM(nh_->get_logger(),
"Could not switch input to: JointJog");
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)))
321 auto result = switch_input_->async_send_request(request_);
322 if (result.get()->success)
324 RCLCPP_INFO_STREAM(nh_->get_logger(),
"Switched to input type: Twist");
328 RCLCPP_WARN_STREAM(nh_->get_logger(),
"Could not switch input to: Twist");
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;
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;
343 RCLCPP_DEBUG(nh_->get_logger(),
"quit");
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;
355 else if (publish_joint)
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;