keyboard_teleop.cpp
Go to the documentation of this file.
1 // Copyright 1996-2019 Cyberbotics Ltd.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "ros/ros.h"
16 
17 #include <webots_ros/Int32Stamped.h>
18 
19 #include <webots_ros/set_float.h>
20 #include <webots_ros/set_int.h>
21 
22 #include <webots_ros/robot_get_device_list.h>
23 
24 #include <std_msgs/String.h>
25 
26 #include <signal.h>
27 #include <stdio.h>
28 
29 #define TIME_STEP 32
30 
31 static int controllerCount;
32 static std::vector<std::string> controllerList;
33 static std::string controllerName;
34 static double lposition = 0;
35 static double rposition = 0;
36 
38 webots_ros::set_float leftWheelSrv;
39 
41 webots_ros::set_float rightWheelSrv;
42 
44 webots_ros::set_int timeStepSrv;
45 
47 webots_ros::set_int enableKeyboardSrv;
48 
49 // catch names of the controllers availables on ROS network
50 void controllerNameCallback(const std_msgs::String::ConstPtr &name) {
52  controllerList.push_back(name->data);
53  ROS_INFO("Controller #%d: %s.", controllerCount, controllerList.back().c_str());
54 }
55 
56 void quit(int sig) {
57  enableKeyboardSrv.request.value = 0;
58  enableKeyboardClient.call(enableKeyboardSrv);
59  timeStepSrv.request.value = 0;
60  timeStepClient.call(timeStepSrv);
61  ROS_INFO("User stopped the 'keyboard_teleop' node.");
62  ros::shutdown();
63  exit(0);
64 }
65 
66 void keyboardCallback(const webots_ros::Int32Stamped::ConstPtr &value) {
67  int key = value->data;
68  int send = 0;
69 
70  switch (key) {
71  case 314:
72  lposition += -0.2;
73  rposition += 0.2;
74  send = 1;
75  break;
76  case 316:
77  lposition += 0.2;
78  rposition += -0.2;
79  send = 1;
80  break;
81  case 315:
82  lposition += 0.2;
83  rposition += 0.2;
84  send = 1;
85  break;
86  case 317:
87  lposition += -0.2;
88  rposition += -0.2;
89  send = 1;
90  break;
91  case 312:
92  ROS_INFO("END.");
93  quit(-1);
94  break;
95  default:
96  send = 0;
97  break;
98  }
99 
100  leftWheelSrv.request.value = lposition;
101  rightWheelSrv.request.value = rposition;
102  if (send) {
103  if (!leftWheelClient.call(leftWheelSrv) || !rightWheelClient.call(rightWheelSrv) || !leftWheelSrv.response.success ||
104  !rightWheelSrv.response.success)
105  ROS_ERROR("Failed to send new position commands to the robot.");
106  }
107  return;
108 }
109 
110 int main(int argc, char **argv) {
111  // create a node named 'keyboard_teleop' on ROS network
112  ros::init(argc, argv, "keyboard_teleop", ros::init_options::AnonymousName);
114 
115  signal(SIGINT, quit);
116 
117  // subscribe to the topic model_name to get the list of availables controllers
118  ros::Subscriber nameSub = n.subscribe("model_name", 100, controllerNameCallback);
119  while (controllerCount == 0 || controllerCount < nameSub.getNumPublishers()) {
120  ros::spinOnce();
121  ros::spinOnce();
122  ros::spinOnce();
123  }
124  ros::spinOnce();
125 
126  // if there is more than one controller available, let the user choose
127  if (controllerCount == 1)
129  else {
130  int wantedController = 0;
131  std::cout << "Choose the # of the controller you want to use:\n";
132  std::cin >> wantedController;
133  if (1 <= wantedController && wantedController <= controllerCount)
134  controllerName = controllerList[wantedController - 1];
135  else {
136  ROS_ERROR("Invalid number for controller choice.");
137  return 1;
138  }
139  }
140  // leave topic once it's not necessary anymore
141  nameSub.shutdown();
142 
143  leftWheelClient = n.serviceClient<webots_ros::set_float>(controllerName + "/left_wheel/set_position");
144  rightWheelClient = n.serviceClient<webots_ros::set_float>(controllerName + "/right_wheel/set_position");
145  timeStepClient = n.serviceClient<webots_ros::set_int>(controllerName + "/robot/time_step");
146  timeStepSrv.request.value = TIME_STEP;
147 
148  enableKeyboardClient = n.serviceClient<webots_ros::set_int>(controllerName + "/keyboard/enable");
149  enableKeyboardSrv.request.value = TIME_STEP;
150  if (enableKeyboardClient.call(enableKeyboardSrv) && enableKeyboardSrv.response.success) {
151  ros::Subscriber sub_keyboard;
152  sub_keyboard = n.subscribe(controllerName + "/keyboard/key", 1, keyboardCallback);
153  while (sub_keyboard.getNumPublishers() == 0) {
154  }
155  ROS_INFO("Keyboard enabled.");
156  ROS_INFO("Use the arrows in Webots window to move the robot.");
157  ROS_INFO("Press the End key to stop the node.");
158 
159  // main loop
160  while (ros::ok()) {
161  ros::spinOnce();
162  if (!timeStepClient.call(timeStepSrv) || !timeStepSrv.response.success)
163  ROS_ERROR("Failed to call service time_step for next step.");
164  }
165  } else
166  ROS_ERROR("Could not enable keyboard, success = %d.", enableKeyboardSrv.response.success);
167 
168  enableKeyboardSrv.request.value = 0;
169  if (!enableKeyboardClient.call(enableKeyboardSrv) || !enableKeyboardSrv.response.success)
170  ROS_ERROR("Could not disable keyboard, success = %d.", enableKeyboardSrv.response.success);
171  timeStepSrv.request.value = 0;
172  timeStepClient.call(timeStepSrv);
173  ros::shutdown();
174  return (0);
175 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void controllerNameCallback(const std_msgs::String::ConstPtr &name)
static double rposition
void keyboardCallback(const webots_ros::Int32Stamped::ConstPtr &value)
ros::ServiceClient timeStepClient
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static std::vector< std::string > controllerList
ros::ServiceClient leftWheelClient
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
static int controllerCount
static std::string controllerName
void quit(int sig)
ros::NodeHandle * n
Definition: pioneer3at.cpp:40
#define ROS_INFO(...)
webots_ros::set_float leftWheelSrv
uint32_t getNumPublishers() const
ROSCPP_DECL bool ok()
ros::ServiceClient rightWheelClient
webots_ros::set_int enableKeyboardSrv
ROSCPP_DECL void shutdown()
webots_ros::set_int timeStepSrv
#define TIME_STEP
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
static double lposition
webots_ros::set_float rightWheelSrv
ros::ServiceClient enableKeyboardClient
int main(int argc, char **argv)


webots_ros
Author(s):
autogenerated on Mon Jul 8 2019 03:19:27