complete_test.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 <geometry_msgs/Twist.h>
16 #include <geometry_msgs/WrenchStamped.h>
17 #include <sensor_msgs/Illuminance.h>
18 #include <sensor_msgs/Image.h>
19 #include <sensor_msgs/Imu.h>
20 #include <sensor_msgs/MagneticField.h>
21 #include <sensor_msgs/NavSatFix.h>
22 #include <sensor_msgs/Range.h>
23 #include <signal.h>
24 #include <std_msgs/Float32MultiArray.h>
25 #include <std_msgs/Float64.h>
26 #include <std_msgs/Float64MultiArray.h>
27 #include <std_msgs/String.h>
28 #include <std_msgs/UInt16.h>
29 #include <std_msgs/UInt8MultiArray.h>
30 #include <webots_ros/BoolStamped.h>
31 #include <webots_ros/Float64Stamped.h>
32 #include <webots_ros/Int32Stamped.h>
33 #include <webots_ros/Int8Stamped.h>
34 #include <webots_ros/RadarTarget.h>
35 #include <webots_ros/RecognitionObject.h>
36 #include <webots_ros/StringStamped.h>
37 #include <cstdlib>
38 #include "ros/ros.h"
39 
40 #include <webots_ros/get_bool.h>
41 #include <webots_ros/get_float.h>
42 #include <webots_ros/get_int.h>
43 #include <webots_ros/get_string.h>
44 #include <webots_ros/get_uint64.h>
45 #include <webots_ros/set_bool.h>
46 #include <webots_ros/set_float.h>
47 #include <webots_ros/set_float_array.h>
48 #include <webots_ros/set_int.h>
49 #include <webots_ros/set_string.h>
50 
51 #include <webots_ros/camera_get_focus_info.h>
52 #include <webots_ros/camera_get_info.h>
53 #include <webots_ros/camera_get_zoom_info.h>
54 #include <webots_ros/display_draw_line.h>
55 #include <webots_ros/display_draw_oval.h>
56 #include <webots_ros/display_draw_pixel.h>
57 #include <webots_ros/display_draw_polygon.h>
58 #include <webots_ros/display_draw_rectangle.h>
59 #include <webots_ros/display_draw_text.h>
60 #include <webots_ros/display_get_info.h>
61 #include <webots_ros/display_image_copy.h>
62 #include <webots_ros/display_image_delete.h>
63 #include <webots_ros/display_image_load.h>
64 #include <webots_ros/display_image_new.h>
65 #include <webots_ros/display_image_paste.h>
66 #include <webots_ros/display_image_save.h>
67 #include <webots_ros/display_set_font.h>
68 #include <webots_ros/field_get_bool.h>
69 #include <webots_ros/field_get_color.h>
70 #include <webots_ros/field_get_count.h>
71 #include <webots_ros/field_get_float.h>
72 #include <webots_ros/field_get_int32.h>
73 #include <webots_ros/field_get_node.h>
74 #include <webots_ros/field_get_rotation.h>
75 #include <webots_ros/field_get_string.h>
76 #include <webots_ros/field_get_type.h>
77 #include <webots_ros/field_get_type_name.h>
78 #include <webots_ros/field_get_vec2f.h>
79 #include <webots_ros/field_get_vec3f.h>
80 #include <webots_ros/field_import_node.h>
81 #include <webots_ros/field_remove.h>
82 #include <webots_ros/field_set_bool.h>
83 #include <webots_ros/field_set_color.h>
84 #include <webots_ros/field_set_float.h>
85 #include <webots_ros/field_set_int32.h>
86 #include <webots_ros/field_set_rotation.h>
87 #include <webots_ros/field_set_string.h>
88 #include <webots_ros/field_set_vec2f.h>
89 #include <webots_ros/field_set_vec3f.h>
90 #include <webots_ros/lidar_get_frequency_info.h>
91 #include <webots_ros/lidar_get_info.h>
92 #include <webots_ros/motor_set_control_pid.h>
93 #include <webots_ros/node_get_center_of_mass.h>
94 #include <webots_ros/node_get_contact_point.h>
95 #include <webots_ros/node_get_field.h>
96 #include <webots_ros/node_get_id.h>
97 #include <webots_ros/node_get_name.h>
98 #include <webots_ros/node_get_number_of_contact_points.h>
99 #include <webots_ros/node_get_orientation.h>
100 #include <webots_ros/node_get_parent_node.h>
101 #include <webots_ros/node_get_position.h>
102 #include <webots_ros/node_get_static_balance.h>
103 #include <webots_ros/node_get_status.h>
104 #include <webots_ros/node_get_type.h>
105 #include <webots_ros/node_get_velocity.h>
106 #include <webots_ros/node_remove.h>
107 #include <webots_ros/node_reset_functions.h>
108 #include <webots_ros/node_set_velocity.h>
109 #include <webots_ros/node_set_visibility.h>
110 #include <webots_ros/pen_set_ink_color.h>
111 #include <webots_ros/range_finder_get_info.h>
112 #include <webots_ros/receiver_get_emitter_direction.h>
113 #include <webots_ros/robot_get_device_list.h>
114 #include <webots_ros/robot_set_mode.h>
115 #include <webots_ros/robot_wait_for_user_input_event.h>
116 #include <webots_ros/save_image.h>
117 #include <webots_ros/speaker_play_sound.h>
118 #include <webots_ros/speaker_speak.h>
119 #include <webots_ros/supervisor_get_from_def.h>
120 #include <webots_ros/supervisor_get_from_id.h>
121 #include <webots_ros/supervisor_movie_start_recording.h>
122 #include <webots_ros/supervisor_set_label.h>
123 #include <webots_ros/supervisor_virtual_reality_headset_get_orientation.h>
124 #include <webots_ros/supervisor_virtual_reality_headset_get_position.h>
125 
126 #define TIME_STEP 32
127 
128 using namespace std;
129 
130 static int model_count;
131 static vector<string> model_list;
132 vector<unsigned char> imageColor;
133 vector<float> imageRangeFinder;
135 double accelerometerValues[3] = {0, 0, 0};
136 double compassValues[3] = {0, 0, 0};
137 double GPSValues[3] = {0, 0, 0};
138 double GyroValues[3] = {0, 0, 0};
139 double inertialUnitValues[4] = {0, 0, 0, 0};
140 double touchSensorValues[3] = {0, 0, 0};
141 
143 webots_ros::set_int time_step_srv;
144 
145 void modelNameCallback(const std_msgs::String::ConstPtr &name) {
146  model_count++;
147  model_list.push_back(name->data);
148  ROS_INFO("Model #%d: %s.", model_count, model_list.back().c_str());
149 }
150 
151 void cameraCallback(const sensor_msgs::Image::ConstPtr &values) {
152  int i = 0;
153  imageColor.resize(values->step * values->height);
154  for (std::vector<unsigned char>::const_iterator it = values->data.begin(); it != values->data.end(); ++it) {
155  imageColor[i] = *it;
156  i++;
157  }
158 }
159 
160 void joystickCallback(const webots_ros::Int8Stamped::ConstPtr &value) {
161  ROS_INFO("Joystick button pressed: %d (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
162 }
163 
164 void keyboardCallback(const webots_ros::Int32Stamped::ConstPtr &value) {
165  ROS_INFO("Keyboard key pressed: %d (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
166 }
167 
168 void radarTargetsCallback(const webots_ros::RadarTarget::ConstPtr &target) {
169  ROS_INFO("Received a radar target with distance=%lf received power=%lf speed=%lf azimuth=%lf (time: %d:%d).",
170  target->distance, target->receivedPower, target->speed, target->azimuth, target->header.stamp.sec,
171  target->header.stamp.nsec);
172 }
173 
174 void radarTargetsNumberCallback(const webots_ros::Int8Stamped::ConstPtr &value) {
175  ROS_INFO("Number of target seen by the radar: %d (time: %d:%d).", value->data, value->header.stamp.sec,
176  value->header.stamp.nsec);
177 }
178 
179 void rangeFinderCallback(const sensor_msgs::Image::ConstPtr &image) {
180  int size = image->width * image->height;
181  imageRangeFinder.resize(size);
182 
183  const float *depth_data = reinterpret_cast<const float *>(&image->data[0]);
184  for (int i = 0; i < size; ++i)
185  imageRangeFinder[i] = depth_data[i];
186 }
187 
188 void lidarCallback(const sensor_msgs::Image::ConstPtr &image) {
189 }
190 
191 void connectorCallback(const webots_ros::Int8Stamped::ConstPtr &value) {
192  connectorPresence = value->data;
193 
194  ROS_INFO("Connector presence: %d (time: %d:%d).", connectorPresence, value->header.stamp.sec, value->header.stamp.nsec);
195 }
196 
197 void accelerometerCallback(const sensor_msgs::Imu::ConstPtr &values) {
198  accelerometerValues[0] = values->linear_acceleration.x;
199  accelerometerValues[1] = values->linear_acceleration.y;
200  accelerometerValues[2] = values->linear_acceleration.z;
201 
202  ROS_INFO("Accelerometer values are x=%f y=%f z=%f (time: %d:%d).", accelerometerValues[0], accelerometerValues[1],
203  accelerometerValues[2], values->header.stamp.sec, values->header.stamp.nsec);
204 }
205 
206 void battery_sensorCallback(const webots_ros::Float64Stamped::ConstPtr &value) {
207  ROS_INFO("Battery level is %f (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
208 }
209 
210 void compassCallback(const sensor_msgs::MagneticField::ConstPtr &values) {
211  compassValues[0] = values->magnetic_field.x;
212  compassValues[1] = values->magnetic_field.y;
213  compassValues[2] = values->magnetic_field.z;
214 
215  ROS_INFO("Compass values are x=%f y=%f z=%f (time: %d:%d).", compassValues[0], compassValues[1], compassValues[2],
216  values->header.stamp.sec, values->header.stamp.nsec);
217 }
218 
219 void distance_sensorCallback(const sensor_msgs::Range::ConstPtr &value) {
220  ROS_INFO("Distance from object is %f (time: %d:%d).", value->range, value->header.stamp.sec, value->header.stamp.nsec);
221 }
222 
223 void GPSCallback(const sensor_msgs::NavSatFix::ConstPtr &values) {
224  GPSValues[0] = values->latitude;
225  GPSValues[1] = values->altitude;
226  GPSValues[2] = values->longitude;
227 
228  ROS_INFO("GPS values are x=%f y=%f z=%f (time: %d:%d).", GPSValues[0], GPSValues[1], GPSValues[2], values->header.stamp.sec,
229  values->header.stamp.nsec);
230 }
231 
232 void GPSSpeedCallback(const webots_ros::Float64Stamped::ConstPtr &value) {
233  ROS_INFO("GPS speed is: %fkm/h (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
234 }
235 
236 void gyroCallback(const sensor_msgs::Imu::ConstPtr &values) {
237  GyroValues[0] = values->angular_velocity.x;
238  GyroValues[1] = values->angular_velocity.y;
239  GyroValues[2] = values->angular_velocity.z;
240 
241  ROS_INFO("Gyro values are x=%f y=%f z=%f (time: %d:%d).", GyroValues[0], GyroValues[1], GyroValues[2],
242  values->header.stamp.sec, values->header.stamp.nsec);
243 }
244 
245 void inertialUnitCallback(const sensor_msgs::Imu::ConstPtr &values) {
246  inertialUnitValues[0] = values->orientation.x;
247  inertialUnitValues[1] = values->orientation.y;
248  inertialUnitValues[2] = values->orientation.z;
249  inertialUnitValues[3] = values->orientation.w;
250 
251  ROS_INFO("Inertial unit values (quaternions) are x=%f y=%f z=%f w=%f (time: %d:%d).", inertialUnitValues[0],
252  inertialUnitValues[1], inertialUnitValues[2], inertialUnitValues[2], values->header.stamp.sec,
253  values->header.stamp.nsec);
254 }
255 
256 void lightSensorCallback(const sensor_msgs::Illuminance::ConstPtr &value) {
257  ROS_INFO("Light intensity is %f.", value->illuminance);
258 }
259 
260 void motorSensorCallback(const std_msgs::Float64::ConstPtr &value) {
261  ROS_INFO("Motor sensor sent value %f.", value->data);
262 }
263 
264 void positionSensorCallback(const webots_ros::Float64Stamped::ConstPtr &value) {
265  ROS_INFO("Position sensor sent value %f (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
266 }
267 
268 void touchSensorCallback(const webots_ros::Float64Stamped::ConstPtr &value) {
269  ROS_INFO("Touch sensor sent value %f (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
270 }
271 
272 void touchSensorBumperCallback(const webots_ros::BoolStamped::ConstPtr &value) {
273  ROS_INFO("Touch sensor sent value %d (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
274 }
275 
276 void touchSensor3DCallback(const geometry_msgs::WrenchStamped::ConstPtr &values) {
277  touchSensorValues[0] = values->wrench.force.x;
278  touchSensorValues[1] = values->wrench.force.y;
279  touchSensorValues[2] = values->wrench.force.z;
280 
281  ROS_INFO("Touch sensor values are x = %f, y = %f and z = %f (time: %d:%d).", touchSensorValues[0], touchSensorValues[1],
282  touchSensorValues[2], values->header.stamp.sec, values->header.stamp.nsec);
283 }
284 
285 void receiverCallback(const webots_ros::StringStamped::ConstPtr &value) {
286  char *message = const_cast<char *>(value->data.c_str());
287  ROS_INFO("Received a message %s.", message);
288 }
289 
290 void quit(int sig) {
291  time_step_srv.request.value = 0;
292  time_step_client.call(time_step_srv);
293  ROS_INFO("User stopped the 'complete_test' node.");
294  ros::shutdown();
295  exit(0);
296 }
297 
298 int main(int argc, char **argv) {
299  string model_name = "my_robot";
300 
301  ros::init(argc, argv, "complete_test", ros::init_options::AnonymousName);
303 
304  signal(SIGINT, quit);
305 
306  ros::Subscriber name_sub = n.subscribe("model_name", 100, modelNameCallback);
307  while (model_count == 0 || model_count < name_sub.getNumPublishers()) {
308  ros::spinOnce();
309  ros::spinOnce();
310  ros::spinOnce();
311  }
312  ros::spinOnce();
313  name_sub.shutdown();
314 
316  // ROBOT METHODS TEST //
318 
319  int mode = 0;
320  string controller_args;
321  string controller_name;
322  string model;
323  string path;
324  string data;
325  vector<string> device_list;
326 
327  time_step_client = n.serviceClient<webots_ros::set_int>(model_name + "/robot/time_step");
328  time_step_srv.request.value = TIME_STEP;
329 
330  if (time_step_client.call(time_step_srv) && time_step_srv.response.success)
331  ROS_INFO("time_step service works.");
332  else
333  ROS_ERROR("Failed to call service time_step to update robot's time step.");
334 
335  ros::ServiceClient get_number_of_devices_client =
336  n.serviceClient<webots_ros::get_int>(model_name + "/robot/get_number_of_devices");
337  webots_ros::get_int get_number_of_devices_srv;
338 
339  if (get_number_of_devices_client.call(get_number_of_devices_srv)) {
340  int number_of_devices = get_number_of_devices_srv.response.value;
341  ROS_INFO("%s has %d devices.", model_name.c_str(), number_of_devices);
342  } else
343  ROS_ERROR("Failed to call service get_number_of_devices.");
344 
345  get_number_of_devices_client.shutdown();
346  time_step_client.call(time_step_srv);
347 
348  ros::ServiceClient device_list_client =
349  n.serviceClient<webots_ros::robot_get_device_list>(model_name + "/robot/get_device_list");
350  webots_ros::robot_get_device_list device_list_srv;
351 
352  if (device_list_client.call(device_list_srv)) {
353  device_list = device_list_srv.response.list;
354  for (unsigned int i = 0; i < device_list.size(); i++)
355  ROS_INFO("Device [%d]: %s.", i, device_list[i].c_str());
356  } else
357  ROS_ERROR("Failed to call service device_list.");
358 
359  device_list_client.shutdown();
360  time_step_client.call(time_step_srv);
361 
362  ros::ServiceClient get_basic_time_step_client =
363  n.serviceClient<webots_ros::get_float>(model_name + "/robot/get_basic_time_step");
364  webots_ros::get_float get_basic_time_step_srv;
365 
366  if (get_basic_time_step_client.call(get_basic_time_step_srv)) {
367  double basic_time_step = get_basic_time_step_srv.response.value;
368  ROS_INFO("%s has a basic time step of %f.", model_name.c_str(), basic_time_step);
369  } else
370  ROS_ERROR("Failed to call service get_basic_time_step.");
371 
372  get_basic_time_step_client.shutdown();
373  time_step_client.call(time_step_srv);
374 
375  ros::ServiceClient get_controller_arguments_client =
376  n.serviceClient<webots_ros::get_string>(model_name + "/robot/get_controller_arguments");
377  webots_ros::get_string get_controller_arguments_srv;
378 
379  if (get_controller_arguments_client.call(get_controller_arguments_srv)) {
380  controller_args = get_controller_arguments_srv.response.value;
381  ROS_INFO("Controller arguments of %s are %s.", model_name.c_str(), controller_args.c_str());
382  } else
383  ROS_ERROR("Failed to call service get_controller_arguments.");
384 
385  get_controller_arguments_client.shutdown();
386  time_step_client.call(time_step_srv);
387 
388  ros::ServiceClient get_controller_name_client =
389  n.serviceClient<webots_ros::get_string>(model_name + "/robot/get_controller_name");
390  webots_ros::get_string get_controller_name_srv;
391 
392  if (get_controller_name_client.call(get_controller_name_srv)) {
393  controller_name = get_controller_name_srv.response.value;
394  ROS_INFO("Controller name of %s is %s.", model_name.c_str(), controller_name.c_str());
395  } else
396  ROS_ERROR("Failed to call service get_controller_name.");
397 
398  get_controller_name_client.shutdown();
399  time_step_client.call(time_step_srv);
400 
401  ros::ServiceClient robot_get_custom_data_client =
402  n.serviceClient<webots_ros::get_string>(model_name + "/robot/get_custom_data");
403  webots_ros::get_string robot_get_custom_data_srv;
404 
405  if (robot_get_custom_data_client.call(robot_get_custom_data_srv)) {
406  data = robot_get_custom_data_srv.response.value;
407  ROS_INFO("Data of %s is %s.", model_name.c_str(), data.c_str());
408  } else
409  ROS_ERROR("Failed to call service robot_get_custom_data.");
410 
411  robot_get_custom_data_client.shutdown();
412  time_step_client.call(time_step_srv);
413 
414  ros::ServiceClient get_mode_client = n.serviceClient<webots_ros::get_int>(model_name + "/robot/get_mode");
415  webots_ros::get_int get_mode_srv;
416 
417  if (get_mode_client.call(get_mode_srv)) {
418  mode = get_mode_srv.response.value;
419  ROS_INFO("Mode of %s is %d.", model_name.c_str(), mode);
420  } else
421  ROS_ERROR("Failed to call service get_mode.");
422 
423  get_mode_client.shutdown();
424  time_step_client.call(time_step_srv);
425 
426  ros::ServiceClient get_model_client = n.serviceClient<webots_ros::get_string>(model_name + "/robot/get_model");
427  webots_ros::get_string get_model_srv;
428 
429  if (get_model_client.call(get_model_srv)) {
430  model = get_model_srv.response.value;
431  ROS_INFO("Model of %s is %s.", model_name.c_str(), model.c_str());
432  } else
433  ROS_ERROR("Failed to call service get_model.");
434 
435  get_model_client.shutdown();
436  time_step_client.call(time_step_srv);
437 
438  ros::ServiceClient get_project_path_client = n.serviceClient<webots_ros::get_string>(model_name + "/robot/get_project_path");
439  webots_ros::get_string get_project_path_srv;
440 
441  if (get_project_path_client.call(get_project_path_srv)) {
442  path = get_project_path_srv.response.value;
443  ROS_INFO("World path of %s is %s.", model_name.c_str(), path.c_str());
444  } else
445  ROS_ERROR("Failed to call service get_project_path.");
446 
447  get_project_path_client.shutdown();
448  time_step_client.call(time_step_srv);
449 
450  // robot_get_world_path
451  ros::ServiceClient get_world_path_client = n.serviceClient<webots_ros::get_string>(model_name + "/robot/get_world_path");
452  webots_ros::get_string get_world_path_srv;
453 
454  if (get_world_path_client.call(get_world_path_srv)) {
455  path = get_world_path_srv.response.value;
456  ROS_INFO("Project path of %s is %s.", model_name.c_str(), path.c_str());
457  } else
458  ROS_ERROR("Failed to call service get_project_path.");
459 
460  get_world_path_client.shutdown();
461  time_step_client.call(time_step_srv);
462 
463  ros::ServiceClient get_supervisor_client = n.serviceClient<webots_ros::get_bool>(model_name + "/robot/get_supervisor");
464  webots_ros::get_bool get_supervisor_srv;
465 
466  if (get_supervisor_client.call(get_supervisor_srv)) {
467  if (get_supervisor_srv.response.value)
468  ROS_INFO("%s is a supervisor.", model_name.c_str());
469  else
470  ROS_ERROR("%s isn't a supervisor.", model_name.c_str());
471  } else
472  ROS_ERROR("Failed to call service get_synchronization.");
473 
474  get_supervisor_client.shutdown();
475  time_step_client.call(time_step_srv);
476 
477  ros::ServiceClient get_synchronization_client =
478  n.serviceClient<webots_ros::get_bool>(model_name + "/robot/get_synchronization");
479  webots_ros::get_bool get_synchronization_srv;
480 
481  if (get_synchronization_client.call(get_synchronization_srv)) {
482  bool synchronization = get_synchronization_srv.response.value;
483  if (synchronization)
484  ROS_INFO("%s is sync.", model_name.c_str());
485  else
486  ROS_INFO("%s isn't sync.", model_name.c_str());
487  } else
488  ROS_ERROR("Failed to call service get_synchronization.");
489 
490  get_synchronization_client.shutdown();
491  time_step_client.call(time_step_srv);
492 
493  ros::ServiceClient get_time_client = n.serviceClient<webots_ros::get_float>(model_name + "/robot/get_time");
494  webots_ros::get_float get_time_srv;
495 
496  if (get_time_client.call(get_time_srv)) {
497  double time = get_time_srv.response.value;
498  ROS_INFO("Time for %s is %f.", model_name.c_str(), time);
499  } else
500  ROS_ERROR("Failed to call service get_time.");
501 
502  get_time_client.shutdown();
503  time_step_client.call(time_step_srv);
504 
505  ros::ServiceClient get_type_client = n.serviceClient<webots_ros::get_int>(model_name + "/robot/get_type");
506  webots_ros::get_int get_type_srv;
507 
508  if (get_type_client.call(get_type_srv)) {
509  int type = get_type_srv.response.value;
510  ROS_INFO("Type of %s is %d.", model_name.c_str(), type);
511  } else
512  ROS_ERROR("Failed to call service get_type.");
513 
514  get_type_client.shutdown();
515  time_step_client.call(time_step_srv);
516 
517  ros::ServiceClient robot_set_custom_data_client =
518  n.serviceClient<webots_ros::set_string>(model_name + "/robot/set_custom_data");
519  webots_ros::set_string robot_set_custom_data_srv;
520 
521  robot_set_custom_data_srv.request.value = "OVERWRITTEN";
522  if (robot_set_custom_data_client.call(robot_set_custom_data_srv)) {
523  if (robot_set_custom_data_srv.response.success)
524  ROS_INFO("Data of %s has been set to %s.", model_name.c_str(), data.c_str());
525  } else
526  ROS_ERROR("Failed to call service robot_set_custom_data.");
527 
528  robot_set_custom_data_client.shutdown();
529  time_step_client.call(time_step_srv);
530 
531  ros::ServiceClient set_mode_client = n.serviceClient<webots_ros::robot_set_mode>(model_name + "/robot/set_mode");
532  webots_ros::robot_set_mode set_mode_srv;
533 
534  set_mode_srv.request.mode = mode;
535  if (set_mode_client.call(set_mode_srv)) {
536  if (set_mode_srv.response.success == 1)
537  ROS_INFO("Mode of %s has been set to %d.", model_name.c_str(), mode);
538  } else
539  ROS_ERROR("Failed to call service set_mode.");
540 
541  set_mode_client.shutdown();
542  time_step_client.call(time_step_srv);
543 
544  ros::ServiceClient enable_keyboard_client = n.serviceClient<webots_ros::set_int>(model_name + "/keyboard/enable");
545  webots_ros::set_int enable_keyboard_srv;
546  ros::Subscriber sub_keyboard;
547 
548  enable_keyboard_srv.request.value = 32;
549  if (enable_keyboard_client.call(enable_keyboard_srv) && enable_keyboard_srv.response.success) {
550  ROS_INFO("Keyboard of %s has been enabled.", model_name.c_str());
551  sub_keyboard = n.subscribe(model_name + "/keyboard/key", 1, keyboardCallback);
552  ROS_INFO("Topics for keyboard initialized.");
553 
554  while (sub_keyboard.getNumPublishers() == 0) {
555  ros::spinOnce();
556  time_step_client.call(time_step_srv);
557  }
558  ROS_INFO("Topics for keyboard connected.");
559  } else
560  ROS_ERROR("Failed to enable keyboard.");
561 
562  ros::ServiceClient wait_for_user_input_event_client =
563  n.serviceClient<webots_ros::robot_wait_for_user_input_event>(model_name + "/robot/wait_for_user_input_event");
564  webots_ros::robot_wait_for_user_input_event wait_for_user_input_event_srv;
565 
566  wait_for_user_input_event_srv.request.eventType = 4; // WB_EVENT_KEYBOARD
567  wait_for_user_input_event_srv.request.timeout = 20;
568  if (wait_for_user_input_event_client.call(wait_for_user_input_event_srv))
569  ROS_INFO("Detected user input event: %d.", wait_for_user_input_event_srv.response.event);
570  else
571  ROS_ERROR("Failed to call service wait_for_user_input_event.");
572 
573  wait_for_user_input_event_client.shutdown();
574  time_step_client.call(time_step_srv);
575 
576  sub_keyboard.shutdown();
577  enable_keyboard_client.shutdown();
578  time_step_client.call(time_step_srv);
579 
581  // BREAK METHODS TEST //
583 
584  // brake_set_damping_constant
585  ros::ServiceClient brake_set_client = n.serviceClient<webots_ros::set_float>(model_name + "/my_brake/set_damping_constant");
586  webots_ros::set_float brake_set_srv;
587  brake_set_srv.request.value = 0.55;
588  if (brake_set_client.call(brake_set_srv) && brake_set_srv.response.success)
589  ROS_INFO("Brake damping constant set to 0.55.");
590  else
591  ROS_ERROR("Failed to call service brake_set_damping_constant.");
592 
593  brake_set_client.shutdown();
594  time_step_client.call(time_step_srv);
595 
596  // brake_get_motor_name
597  ros::ServiceClient brake_get_motor_name_client =
598  n.serviceClient<webots_ros::get_string>(model_name + "/my_brake/get_motor_name");
599  webots_ros::get_string brake_get_motor_name_srv;
600  if (brake_get_motor_name_client.call(brake_get_motor_name_srv)) {
601  ROS_INFO("Linear motor name returned from Brake API %s.", brake_get_motor_name_srv.response.value.c_str());
602  if (brake_get_motor_name_srv.response.value.compare("linear_motor") != 0)
603  ROS_ERROR("Failed to call service brake_get_motor_name: received '%s' instead of 'linear_motor'",
604  brake_get_motor_name_srv.response.value.c_str());
605  } else
606  ROS_ERROR("Failed to call service brake_get_motor_name.");
607 
608  brake_get_motor_name_client.shutdown();
609  time_step_client.call(time_step_srv);
610 
612  // CAMERA METHODS TEST //
614 
615  // camera_set_focal_distance
616  double focal_distance = 0.33;
617  ros::ServiceClient camera_set_client = n.serviceClient<webots_ros::set_float>(model_name + "/camera/set_focal_distance");
618  webots_ros::set_float camera_set_focal_distance_srv;
619  camera_set_focal_distance_srv.request.value = focal_distance;
620  if (camera_set_client.call(camera_set_focal_distance_srv) && camera_set_focal_distance_srv.response.success)
621  ROS_INFO("Camera focal distance set to %f.", focal_distance);
622  else
623  ROS_ERROR("Failed to call service camera_set_focal_distance.");
624 
625  camera_set_client.shutdown();
626  time_step_client.call(time_step_srv);
627 
628  // camera_set_fov
629  double fov = 1.33;
630  camera_set_client = n.serviceClient<webots_ros::set_float>(model_name + "/camera/set_fov");
631  webots_ros::set_float camera_set_fov_srv;
632  camera_set_fov_srv.request.value = fov;
633  if (camera_set_client.call(camera_set_fov_srv) && camera_set_fov_srv.response.success)
634  ROS_INFO("Camera fov set to %f.", fov);
635  else
636  ROS_ERROR("Failed to call service camera_set_fov.");
637 
638  camera_set_client.shutdown();
639  time_step_client.call(time_step_srv);
640 
641  // camera enable
642  ros::ServiceClient enable_camera_client;
643  webots_ros::set_int camera_srv;
644  ros::Subscriber sub_camera_color;
645 
646  enable_camera_client = n.serviceClient<webots_ros::set_int>(model_name + "/camera/enable");
647  camera_srv.request.value = TIME_STEP;
648  if (enable_camera_client.call(camera_srv) && camera_srv.response.success) {
649  ROS_INFO("Camera enabled.");
650  sub_camera_color = n.subscribe(model_name + "/camera/image", 1, cameraCallback);
651  ROS_INFO("Topic for camera color initialized.");
652  while (sub_camera_color.getNumPublishers() == 0) {
653  ros::spinOnce();
654  time_step_client.call(time_step_srv);
655  }
656  ROS_INFO("Topic for camera color connected.");
657  } else {
658  if (camera_srv.response.success == -1)
659  ROS_ERROR("Sampling period is not valid.");
660  ROS_ERROR("Failed to enable camera.");
661  return 1;
662  }
663 
664  sub_camera_color.shutdown();
665  enable_camera_client.shutdown();
666  time_step_client.call(time_step_srv);
667 
668  // camera_get_info
669  ros::ServiceClient get_info_client = n.serviceClient<webots_ros::camera_get_info>(model_name + "/camera/get_info");
670  webots_ros::camera_get_info get_info_srv;
671  if (get_info_client.call(get_info_srv))
672  ROS_INFO("Camera of %s has a width of %d, a height of %d, a field of view of %f, a near range of %f.", model_name.c_str(),
673  get_info_srv.response.width, get_info_srv.response.height, get_info_srv.response.Fov,
674  get_info_srv.response.nearRange);
675  else
676  ROS_ERROR("Failed to call service camera_get_info.");
677  if (get_info_srv.response.Fov != fov)
678  ROS_ERROR("Failed to set camera fov.");
679 
680  get_info_client.shutdown();
681  time_step_client.call(time_step_srv);
682 
683  // camera_get_focus_info
684  get_info_client = n.serviceClient<webots_ros::camera_get_focus_info>(model_name + "/camera/get_focus_info");
685  webots_ros::camera_get_focus_info camera_get_focus_info_srv;
686  if (get_info_client.call(camera_get_focus_info_srv))
687  ROS_INFO("Camera of %s has focalLength %f, focalDistance %f, maxFocalDistance %f, and minFocalDistance %f.",
688  model_name.c_str(), camera_get_focus_info_srv.response.focalLength,
689  camera_get_focus_info_srv.response.focalDistance, camera_get_focus_info_srv.response.maxFocalDistance,
690  camera_get_focus_info_srv.response.minFocalDistance);
691  else
692  ROS_ERROR("Failed to call service camera_get_focus_info.");
693  if (camera_get_focus_info_srv.response.focalDistance != focal_distance)
694  ROS_ERROR("Failed to set camera focal distance.");
695 
696  get_info_client.shutdown();
697  time_step_client.call(time_step_srv);
698 
699  // camera_get_zoom_info
700  get_info_client = n.serviceClient<webots_ros::camera_get_zoom_info>(model_name + "/camera/get_zoom_info");
701  webots_ros::camera_get_zoom_info camera_get_zoom_info_srv;
702  if (get_info_client.call(camera_get_zoom_info_srv))
703  ROS_INFO("Camera of %s has min fov %f, anf max fov %f.", model_name.c_str(), camera_get_zoom_info_srv.response.minFov,
704  camera_get_zoom_info_srv.response.maxFov);
705  else
706  ROS_ERROR("Failed to call service camera_get_zoom_info.");
707 
708  get_info_client.shutdown();
709  time_step_client.call(time_step_srv);
710 
711  // check presence of recognition capability
712  get_info_client = n.serviceClient<webots_ros::get_bool>(model_name + "/camera/has_recognition");
713  webots_ros::get_bool camera_has_recognition_srv;
714  if (get_info_client.call(camera_has_recognition_srv))
715  if (camera_has_recognition_srv.response.value)
716  ROS_INFO("Recognition capability of camera of %s found.", model_name.c_str());
717  else
718  ROS_ERROR("Recognition capability of camera of %s not found.", model_name.c_str());
719  else
720  ROS_ERROR("Failed to call service camera_get_zoom_info.");
721 
722  get_info_client.shutdown();
723  time_step_client.call(time_step_srv);
724 
725  // camera_save_image
726  ros::ServiceClient save_image_client = n.serviceClient<webots_ros::save_image>(model_name + "/camera/save_image");
727  webots_ros::save_image save_image_srv;
728  save_image_srv.request.filename = std::string(getenv("HOME")) + std::string("/test_image_camera.png");
729  save_image_srv.request.quality = 100;
730 
731  if (save_image_client.call(save_image_srv) && save_image_srv.response.success == 1)
732  ROS_INFO("Image saved.");
733  else
734  ROS_ERROR("Failed to call service save_image.");
735 
736  save_image_client.shutdown();
737  time_step_client.call(time_step_srv);
738 
739  ROS_INFO("Camera disabled.");
740 
742  // DEVICE METHODS TEST //
744 
745  // device_get_name
746  ros::ServiceClient device_get_name_client = n.serviceClient<webots_ros::get_string>(model_name + "/camera/get_name");
747  webots_ros::get_string device_get_name_srv;
748  if (device_get_name_client.call(device_get_name_srv))
749  ROS_INFO("Camera device name: %s.", device_get_name_srv.response.value.c_str());
750  else
751  ROS_ERROR("Failed to call service get_name.");
752 
753  device_get_name_client.shutdown();
754  time_step_client.call(time_step_srv);
755 
756  // device_get_name
757  ros::ServiceClient device_get_model_client = n.serviceClient<webots_ros::get_string>(model_name + "/camera/get_model");
758  webots_ros::get_string device_get_model_srv;
759  if (device_get_model_client.call(device_get_model_srv))
760  ROS_INFO("Camera device model: %s.", device_get_model_srv.response.value.c_str());
761  else
762  ROS_ERROR("Failed to call service get_model.");
763 
764  device_get_model_client.shutdown();
765  time_step_client.call(time_step_srv);
766 
768  // ACCELEROMETER METHODS TEST //
770 
771  ros::ServiceClient set_accelerometer_client;
772  webots_ros::set_int accelerometer_srv;
773  ros::Subscriber sub_accelerometer_32;
774  ros::Subscriber sub_accelerometer_64;
775 
776  set_accelerometer_client = n.serviceClient<webots_ros::set_int>(model_name + "/accelerometer/enable");
777 
778  accelerometer_srv.request.value = 64;
779  if (set_accelerometer_client.call(accelerometer_srv) && accelerometer_srv.response.success) {
780  sub_accelerometer_64 = n.subscribe(model_name + "/accelerometer/values", 1, accelerometerCallback);
781  while (sub_accelerometer_64.getNumPublishers() == 0) {
782  ros::spinOnce();
783  time_step_client.call(time_step_srv);
784  }
785  } else {
786  if (accelerometer_srv.response.success == -1)
787  ROS_ERROR("Sampling period is not valid.");
788  ROS_ERROR("Failed to enable accelerometer.");
789  return 1;
790  }
791 
792  sub_accelerometer_64.shutdown();
793  time_step_client.call(time_step_srv);
794 
795  ros::ServiceClient sampling_period_accelerometer_client;
796  webots_ros::get_int sampling_period_accelerometer_srv;
797 
798  sampling_period_accelerometer_client =
799  n.serviceClient<webots_ros::get_int>(model_name + "/accelerometer/get_sampling_period");
800  sampling_period_accelerometer_client.call(sampling_period_accelerometer_srv);
801  ROS_INFO("Accelerometer is enabled with a sampling period of %d.", sampling_period_accelerometer_srv.response.value);
802 
803  accelerometer_srv.request.value = 32;
804  if (set_accelerometer_client.call(accelerometer_srv) && accelerometer_srv.response.success) {
805  sub_accelerometer_32 = n.subscribe(model_name + "/accelerometer/values", 1, accelerometerCallback);
806  while (sub_accelerometer_32.getNumPublishers() == 0) {
807  ros::spinOnce();
808  time_step_client.call(time_step_srv);
809  }
810  } else {
811  if (accelerometer_srv.response.success == -1)
812  ROS_ERROR("Sampling period is not valid.");
813  ROS_ERROR("Failed to enable accelerometer.");
814  return 1;
815  }
816 
817  sub_accelerometer_32.shutdown();
818  set_accelerometer_client.shutdown();
819  time_step_client.call(time_step_srv);
820 
821  sampling_period_accelerometer_client.call(sampling_period_accelerometer_srv);
822  ROS_INFO("Accelerometer is enabled with a sampling period of %d.", sampling_period_accelerometer_srv.response.value);
823 
824  // wait for webots to detect shutdown of topics and to disable the sensor afterwards
825  time_step_client.call(time_step_srv);
826  time_step_client.call(time_step_srv);
827  time_step_client.call(time_step_srv);
828 
829  sampling_period_accelerometer_client.call(sampling_period_accelerometer_srv);
830  ROS_INFO("Accelerometer is disabled (sampling period is %d).", sampling_period_accelerometer_srv.response.value);
831 
832  sampling_period_accelerometer_client.shutdown();
833  time_step_client.call(time_step_srv);
834 
836  // BATTERY SENSOR METHODS TEST //
838 
839  ros::ServiceClient set_battery_sensor_client;
840  webots_ros::set_int battery_sensor_srv;
841  ros::Subscriber sub_battery_sensor_32;
842  set_battery_sensor_client = n.serviceClient<webots_ros::set_int>(model_name + "/battery_sensor/enable");
843 
844  ros::ServiceClient sampling_period_battery_sensor_client;
845  webots_ros::get_int sampling_period_battery_sensor_srv;
846  sampling_period_battery_sensor_client =
847  n.serviceClient<webots_ros::get_int>(model_name + "/battery_sensor/get_sampling_period");
848 
849  battery_sensor_srv.request.value = 32;
850  if (set_battery_sensor_client.call(battery_sensor_srv) && battery_sensor_srv.response.success) {
851  ROS_INFO("Battery_sensor enabled.");
852  sub_battery_sensor_32 = n.subscribe(model_name + "/battery_sensor/value", 1, battery_sensorCallback);
853  while (sub_battery_sensor_32.getNumPublishers() == 0) {
854  ros::spinOnce();
855  time_step_client.call(time_step_srv);
856  }
857  } else {
858  if (!battery_sensor_srv.response.success)
859  ROS_ERROR("Sampling period is not valid.");
860  ROS_ERROR("Failed to enable battery_sensor.");
861  return 1;
862  }
863 
864  sub_battery_sensor_32.shutdown();
865 
866  time_step_client.call(time_step_srv);
867 
868  sampling_period_battery_sensor_client.call(sampling_period_battery_sensor_srv);
869  ROS_INFO("Battery_sensor is enabled with a sampling period of %d.", sampling_period_battery_sensor_srv.response.value);
870 
871  time_step_client.call(time_step_srv);
872 
873  time_step_client.call(time_step_srv);
874  time_step_client.call(time_step_srv);
875  time_step_client.call(time_step_srv);
876 
877  sampling_period_battery_sensor_client.call(sampling_period_battery_sensor_srv);
878  ROS_INFO("Battery_sensor is disabled (sampling period is %d).", sampling_period_battery_sensor_srv.response.value);
879 
880  set_battery_sensor_client.shutdown();
881  sampling_period_battery_sensor_client.shutdown();
882  time_step_client.call(time_step_srv);
883 
885  // COMPASS METHODS TEST //
887 
888  ros::ServiceClient set_compass_client;
889  webots_ros::set_int compass_srv;
890  ros::Subscriber sub_compass_32;
891  set_compass_client = n.serviceClient<webots_ros::set_int>(model_name + "/compass/enable");
892 
893  ros::ServiceClient sampling_period_compass_client;
894  webots_ros::get_int sampling_period_compass_srv;
895  sampling_period_compass_client = n.serviceClient<webots_ros::get_int>(model_name + "/compass/get_sampling_period");
896 
897  compass_srv.request.value = 32;
898  if (set_compass_client.call(compass_srv) && compass_srv.response.success == 1) {
899  ROS_INFO("Compass enabled.");
900  sub_compass_32 = n.subscribe(model_name + "/compass/values", 1, compassCallback);
901  while (sub_compass_32.getNumPublishers() == 0) {
902  ros::spinOnce();
903  time_step_client.call(time_step_srv);
904  }
905  } else {
906  if (compass_srv.response.success == -1)
907  ROS_ERROR("Sampling period is not valid.");
908  ROS_ERROR("Failed to enable compass.");
909  return 1;
910  }
911 
912  sub_compass_32.shutdown();
913 
914  time_step_client.call(time_step_srv);
915 
916  sampling_period_compass_client.call(sampling_period_compass_srv);
917  ROS_INFO("Compass is enabled with a sampling period of %d.", sampling_period_compass_srv.response.value);
918 
919  time_step_client.call(time_step_srv);
920 
921  time_step_client.call(time_step_srv);
922  time_step_client.call(time_step_srv);
923  time_step_client.call(time_step_srv);
924 
925  sampling_period_compass_client.call(sampling_period_compass_srv);
926  ROS_INFO("Compass is disabled (sampling period is %d).", sampling_period_compass_srv.response.value);
927 
928  set_compass_client.shutdown();
929  sampling_period_compass_client.shutdown();
930  time_step_client.call(time_step_srv);
931 
933  // CONNECTOR METHODS TEST //
935 
936  ros::ServiceClient connector_enable_presence_client;
937  webots_ros::set_int connector_srv;
938  ros::Subscriber sub_connector;
939  connector_enable_presence_client = n.serviceClient<webots_ros::set_int>(model_name + "/connector/presence_sensor/enable");
940 
941  connector_srv.request.value = 32;
942  if (connector_enable_presence_client.call(connector_srv) && connector_srv.response.success) {
943  ROS_INFO("Connector's presence sensor enabled.");
944  sub_connector = n.subscribe(model_name + "/connector/presence", 1, connectorCallback);
945  while (sub_connector.getNumPublishers() == 0) {
946  ros::spinOnce();
947  time_step_client.call(time_step_srv);
948  }
949  } else {
950  if (!connector_srv.response.success)
951  ROS_ERROR("Sampling period is not valid.");
952  ROS_ERROR("Failed to enable connector's presence sensor.");
953  return 1;
954  }
955 
956  sub_connector.shutdown();
957 
958  time_step_client.call(time_step_srv);
959  time_step_client.call(time_step_srv);
960  time_step_client.call(time_step_srv);
961 
962  connector_srv.request.value = 0;
963  if (connector_enable_presence_client.call(connector_srv) && connector_srv.response.success)
964  ROS_INFO("Connector's presence sensor disabled.");
965  else {
966  if (!connector_srv.response.success)
967  ROS_ERROR("Sampling period is not valid.");
968  ROS_ERROR("Failed to disable connector's presence sensor.");
969  return 1;
970  }
971 
972  ros::ServiceClient connector_lock_client;
973  webots_ros::set_bool connector_lock_srv;
974  connector_lock_client = n.serviceClient<webots_ros::set_bool>(model_name + "/connector/lock");
975 
976  connector_lock_srv.request.value = true;
977  if (connector_lock_client.call(connector_lock_srv) && connector_lock_srv.response.success)
978  ROS_INFO("Connector has been locked.");
979  else
980  ROS_INFO("Failed to lock connector.");
981 
982  connector_lock_client.shutdown();
983  connector_enable_presence_client.shutdown();
984  time_step_client.call(time_step_srv);
985 
987  // DISPLAY METHODS TEST //
989 
990  ros::ServiceClient display_get_info_client;
991  webots_ros::display_get_info display_get_info_srv;
992  display_get_info_client = n.serviceClient<webots_ros::display_get_info>(model_name + "/display/get_info");
993 
994  display_get_info_client.call(display_get_info_srv);
995  ROS_INFO("Display's width is %d and its height is %d.", display_get_info_srv.response.width,
996  display_get_info_srv.response.height);
997 
998  display_get_info_client.shutdown();
999  time_step_client.call(time_step_srv);
1000 
1001  ros::ServiceClient display_set_color_client;
1002  webots_ros::set_int display_set_color_srv;
1003  display_set_color_client = n.serviceClient<webots_ros::set_int>(model_name + "/display/set_color");
1004 
1005  display_set_color_srv.request.value = 0xFF0000;
1006  if (display_set_color_client.call(display_set_color_srv) && display_set_color_srv.response.success)
1007  ROS_INFO("Display's color has been updated.");
1008  else
1009  ROS_ERROR("Failed to call service display_set_color. Success = %d.", display_set_color_srv.response.success);
1010 
1011  display_set_color_client.shutdown();
1012  time_step_client.call(time_step_srv);
1013 
1014  ros::ServiceClient display_set_alpha_client;
1015  webots_ros::set_float display_set_alpha_srv;
1016  display_set_alpha_client = n.serviceClient<webots_ros::set_float>(model_name + "/display/set_alpha");
1017 
1018  display_set_alpha_srv.request.value = 1.0;
1019  if (display_set_alpha_client.call(display_set_alpha_srv) && display_set_alpha_srv.response.success)
1020  ROS_INFO("Display's alpha has been updated.");
1021  else
1022  ROS_ERROR("Failed to call service display_set_alpha.");
1023 
1024  display_set_alpha_client.shutdown();
1025  time_step_client.call(time_step_srv);
1026 
1027  ros::ServiceClient display_set_opacity_client;
1028  webots_ros::set_float display_set_opacity_srv;
1029  display_set_opacity_client = n.serviceClient<webots_ros::set_float>(model_name + "/display/set_opacity");
1030 
1031  display_set_opacity_srv.request.value = 1.0;
1032  if (display_set_opacity_client.call(display_set_opacity_srv) && display_set_opacity_srv.response.success)
1033  ROS_INFO("Display's opacity has been updated.");
1034  else
1035  ROS_ERROR("Failed to call service display_set_opacity.");
1036 
1037  display_set_opacity_client.shutdown();
1038  time_step_client.call(time_step_srv);
1039 
1040  ros::ServiceClient display_set_font_client;
1041  webots_ros::display_set_font display_set_font_srv;
1042  display_set_font_client = n.serviceClient<webots_ros::display_set_font>(model_name + "/display/set_font");
1043 
1044  display_set_font_srv.request.font = "Arial";
1045  display_set_font_srv.request.size = 8;
1046  display_set_font_srv.request.antiAliasing = 0;
1047  if (display_set_font_client.call(display_set_font_srv) && display_set_font_srv.response.success == 1)
1048  ROS_INFO("Display's font has been updated.");
1049  else
1050  ROS_ERROR("Failed to call service display_set_font. Success = %d.", display_set_font_srv.response.success);
1051 
1052  display_set_font_client.shutdown();
1053  time_step_client.call(time_step_srv);
1054 
1055  ros::ServiceClient display_draw_pixel_client;
1056  webots_ros::display_draw_pixel display_draw_pixel_srv;
1057  display_draw_pixel_client = n.serviceClient<webots_ros::display_draw_pixel>(model_name + "/display/draw_pixel");
1058 
1059  display_draw_pixel_srv.request.x1 = 10;
1060  display_draw_pixel_srv.request.y1 = 10;
1061  if (display_draw_pixel_client.call(display_draw_pixel_srv) && display_draw_pixel_srv.response.success == 1)
1062  ROS_INFO("Pixel drawn at x =32 and y = 32 on the display.");
1063  else
1064  ROS_ERROR("Failed to call service display_draw_pixel. Success = %d.", display_draw_pixel_srv.response.success);
1065 
1066  display_draw_pixel_client.shutdown();
1067  time_step_client.call(time_step_srv);
1068 
1069  ros::ServiceClient display_draw_line_client;
1070  webots_ros::display_draw_line display_draw_line_srv;
1071  display_draw_line_client = n.serviceClient<webots_ros::display_draw_line>(model_name + "/display/draw_line");
1072 
1073  display_draw_line_srv.request.x1 = 32;
1074  display_draw_line_srv.request.x2 = 63;
1075  display_draw_line_srv.request.y1 = 32;
1076  display_draw_line_srv.request.y2 = 42;
1077  if (display_draw_line_client.call(display_draw_line_srv) && display_draw_line_srv.response.success == 1)
1078  ROS_INFO("Line drawn at x =32 and y = 32 on the display.");
1079  else
1080  ROS_ERROR("Failed to call service display_draw_line. Success = %d.", display_draw_line_srv.response.success);
1081 
1082  display_draw_line_client.shutdown();
1083  time_step_client.call(time_step_srv);
1084 
1085  ros::ServiceClient display_draw_rectangle_client;
1086  webots_ros::display_draw_rectangle display_draw_rectangle_srv;
1087  display_draw_rectangle_client = n.serviceClient<webots_ros::display_draw_rectangle>(model_name + "/display/draw_rectangle");
1088 
1089  display_draw_rectangle_srv.request.x = 2;
1090  display_draw_rectangle_srv.request.y = 32;
1091  display_draw_rectangle_srv.request.width = 10;
1092  display_draw_rectangle_srv.request.height = 5;
1093  if (display_draw_rectangle_client.call(display_draw_rectangle_srv) && display_draw_rectangle_srv.response.success == 1)
1094  ROS_INFO("Rectangle drawn at x =32 and y = 32 with width = 10 and height = 5 on the display.");
1095  else
1096  ROS_ERROR("Failed to call service display_draw_rectangle. Success = %d.", display_draw_rectangle_srv.response.success);
1097 
1098  display_draw_rectangle_client.shutdown();
1099  time_step_client.call(time_step_srv);
1100 
1101  ros::ServiceClient display_draw_oval_client;
1102  webots_ros::display_draw_oval display_draw_oval_srv;
1103  display_draw_oval_client = n.serviceClient<webots_ros::display_draw_oval>(model_name + "/display/draw_oval");
1104 
1105  display_draw_oval_srv.request.cx = 32;
1106  display_draw_oval_srv.request.cy = 6;
1107  display_draw_oval_srv.request.a = 10;
1108  display_draw_oval_srv.request.b = 5;
1109 
1110  if (display_draw_oval_client.call(display_draw_oval_srv) && display_draw_oval_srv.response.success == 1)
1111  ROS_INFO("Oval drawn at x =32 and y = 6 and axes a = 10 and b = 5 on the display.");
1112  else
1113  ROS_ERROR("Failed to call service display_draw_oval. Success = %d.", display_draw_oval_srv.response.success);
1114 
1115  display_draw_oval_client.shutdown();
1116  time_step_client.call(time_step_srv);
1117 
1118  ros::ServiceClient display_draw_polygon_client;
1119  webots_ros::display_draw_polygon display_draw_polygon_srv;
1120  display_draw_polygon_client = n.serviceClient<webots_ros::display_draw_polygon>(model_name + "/display/draw_polygon");
1121 
1122  display_draw_polygon_srv.request.x.push_back(55);
1123  display_draw_polygon_srv.request.y.push_back(55);
1124  display_draw_polygon_srv.request.x.push_back(50);
1125  display_draw_polygon_srv.request.y.push_back(50);
1126  display_draw_polygon_srv.request.x.push_back(45);
1127  display_draw_polygon_srv.request.y.push_back(45);
1128  display_draw_polygon_srv.request.x.push_back(45);
1129  display_draw_polygon_srv.request.y.push_back(55);
1130  display_draw_polygon_srv.request.x.push_back(40);
1131  display_draw_polygon_srv.request.y.push_back(50);
1132  display_draw_polygon_srv.request.size = 5;
1133  if (display_draw_polygon_client.call(display_draw_polygon_srv) && display_draw_polygon_srv.response.success == 1)
1134  ROS_INFO("Polygon drawn on the display.");
1135  else
1136  ROS_ERROR("Failed to call service display_draw_polygon. Success = %d.", display_draw_polygon_srv.response.success);
1137 
1138  display_draw_polygon_client.shutdown();
1139  time_step_client.call(time_step_srv);
1140 
1141  ros::ServiceClient display_draw_text_client;
1142  webots_ros::display_draw_text display_draw_text_srv;
1143  display_draw_text_client = n.serviceClient<webots_ros::display_draw_text>(model_name + "/display/draw_text");
1144 
1145  display_draw_text_srv.request.x = 10;
1146  display_draw_text_srv.request.y = 52;
1147  display_draw_text_srv.request.text = "hello world";
1148  if (display_draw_text_client.call(display_draw_text_srv) && display_draw_text_srv.response.success == 1)
1149  ROS_INFO("Hello World written at x =10 and y = 52 on the display.");
1150  else
1151  ROS_ERROR("Failed to call service display_draw_text. Success = %d.", display_draw_text_srv.response.success);
1152 
1153  display_draw_text_client.shutdown();
1154  time_step_client.call(time_step_srv);
1155 
1156  ros::ServiceClient display_fill_rectangle_client;
1157  webots_ros::display_draw_rectangle display_fill_rectangle_srv;
1158  display_fill_rectangle_client = n.serviceClient<webots_ros::display_draw_rectangle>(model_name + "/display/fill_rectangle");
1159 
1160  display_fill_rectangle_srv.request.x = 2;
1161  display_fill_rectangle_srv.request.y = 32;
1162  display_fill_rectangle_srv.request.width = 10;
1163  display_fill_rectangle_srv.request.height = 5;
1164  if (display_fill_rectangle_client.call(display_fill_rectangle_srv) && display_fill_rectangle_srv.response.success == 1)
1165  ROS_INFO("Rectangle filled at x =32 and y = 32 with width = 10 and height = 5 on the display.");
1166  else
1167  ROS_ERROR("Failed to call service display_fill_rectangle. Success = %d.", display_fill_rectangle_srv.response.success);
1168 
1169  display_fill_rectangle_client.shutdown();
1170  time_step_client.call(time_step_srv);
1171 
1172  ros::ServiceClient display_fill_oval_client;
1173  webots_ros::display_draw_oval display_fill_oval_srv;
1174  display_fill_oval_client = n.serviceClient<webots_ros::display_draw_oval>(model_name + "/display/fill_oval");
1175 
1176  display_fill_oval_srv.request.cx = 32;
1177  display_fill_oval_srv.request.cy = 6;
1178  display_fill_oval_srv.request.a = 10;
1179  display_fill_oval_srv.request.b = 5;
1180 
1181  if (display_fill_oval_client.call(display_fill_oval_srv) && display_fill_oval_srv.response.success == 1)
1182  ROS_INFO("Oval filled at x =32 and y = 6 and axes a = 10 and b = 5 on the display.");
1183  else
1184  ROS_ERROR("Failed to call service display_fill_oval. Success = %d.", display_fill_oval_srv.response.success);
1185 
1186  display_fill_oval_client.shutdown();
1187  time_step_client.call(time_step_srv);
1188 
1189  ros::ServiceClient display_fill_polygon_client;
1190  webots_ros::display_draw_polygon display_fill_polygon_srv;
1191  display_fill_polygon_client = n.serviceClient<webots_ros::display_draw_polygon>(model_name + "/display/fill_polygon");
1192 
1193  display_fill_polygon_srv.request.x.push_back(55);
1194  display_fill_polygon_srv.request.y.push_back(55);
1195  display_fill_polygon_srv.request.x.push_back(50);
1196  display_fill_polygon_srv.request.y.push_back(50);
1197  display_fill_polygon_srv.request.x.push_back(45);
1198  display_fill_polygon_srv.request.y.push_back(45);
1199  display_fill_polygon_srv.request.x.push_back(45);
1200  display_fill_polygon_srv.request.y.push_back(55);
1201  display_fill_polygon_srv.request.x.push_back(40);
1202  display_fill_polygon_srv.request.y.push_back(50);
1203  display_fill_polygon_srv.request.size = 5;
1204  if (display_fill_polygon_client.call(display_fill_polygon_srv) && display_fill_polygon_srv.response.success == 1)
1205  ROS_INFO("Polygon filled on the display.");
1206  else
1207  ROS_ERROR("Failed to call service display_fill_polygon. Success = %d.", display_fill_polygon_srv.response.success);
1208 
1209  display_fill_polygon_client.shutdown();
1210  time_step_client.call(time_step_srv);
1211  time_step_client.call(time_step_srv);
1212  time_step_client.call(time_step_srv);
1213 
1214  ros::ServiceClient display_image_new_client;
1215  webots_ros::display_image_new display_image_new_srv;
1216  display_image_new_client = n.serviceClient<webots_ros::display_image_new>(model_name + "/display/image_new");
1217 
1218  display_image_new_srv.request.format = 3;
1219  display_image_new_srv.request.width = 10;
1220  display_image_new_srv.request.height = 5;
1221  display_image_new_srv.request.data.push_back(1);
1222  display_image_new_srv.request.data.push_back(2);
1223  display_image_new_srv.request.data.push_back(5);
1224  display_image_new_srv.request.data.push_back(3);
1225  display_image_new_srv.request.data.push_back(4);
1226  display_image_new_client.call(display_image_new_srv);
1227  ROS_INFO("New image created.");
1228  uint64_t new_image = display_image_new_srv.response.ir;
1229 
1230  display_image_new_client.shutdown();
1231  time_step_client.call(time_step_srv);
1232 
1233  ros::ServiceClient display_image_copy_client;
1234  webots_ros::display_image_copy display_image_copy_srv;
1235  display_image_copy_client = n.serviceClient<webots_ros::display_image_copy>(model_name + "/display/image_copy");
1236 
1237  display_image_copy_srv.request.x = 0;
1238  display_image_copy_srv.request.y = 32;
1239  display_image_copy_srv.request.width = 64;
1240  display_image_copy_srv.request.height = 32;
1241  display_image_copy_client.call(display_image_copy_srv);
1242  ROS_INFO("Image copied.");
1243  uint64_t copy_image = display_image_copy_srv.response.ir;
1244 
1245  display_image_copy_client.shutdown();
1246  time_step_client.call(time_step_srv);
1247 
1248  ros::ServiceClient display_image_paste_client;
1249  webots_ros::display_image_paste display_image_paste_srv;
1250  display_image_paste_client = n.serviceClient<webots_ros::display_image_paste>(model_name + "/display/image_paste");
1251 
1252  display_image_paste_srv.request.ir = copy_image;
1253  display_image_paste_srv.request.x = 0;
1254  display_image_paste_srv.request.y = 0;
1255  display_image_paste_srv.request.blend = 1;
1256  if (display_image_paste_client.call(display_image_paste_srv) && display_image_paste_srv.response.success == 1)
1257  ROS_INFO("Image successfully copy/paste.");
1258  else
1259  ROS_ERROR("Failed to call service display_image_paste to paste image.");
1260 
1261  display_image_paste_client.shutdown();
1262  time_step_client.call(time_step_srv);
1263  time_step_client.call(time_step_srv);
1264  time_step_client.call(time_step_srv);
1265 
1266  ros::ServiceClient display_image_save_client;
1267  webots_ros::display_image_save display_image_save_srv;
1268  display_image_save_client = n.serviceClient<webots_ros::display_image_save>(model_name + "/display/image_save");
1269 
1270  display_image_save_srv.request.ir = copy_image;
1271  display_image_save_srv.request.filename = std::string(getenv("HOME")) + std::string("/copy_image.png");
1272  if (display_image_save_client.call(display_image_save_srv) && display_image_save_srv.response.success == 1)
1273  ROS_INFO("Image successfully saved.");
1274  else
1275  ROS_ERROR("Failed to call service display_image_save to save image.");
1276 
1277  display_image_save_client.shutdown();
1278  time_step_client.call(time_step_srv);
1279 
1280  ros::ServiceClient display_image_load_client;
1281  webots_ros::display_image_load display_image_load_srv;
1282  display_image_load_client = n.serviceClient<webots_ros::display_image_load>(model_name + "/display/image_load");
1283 
1284  display_image_load_srv.request.filename = std::string(getenv("HOME")) + std::string("/test_image_camera.png");
1285  display_image_load_client.call(display_image_load_srv);
1286  ROS_INFO("Image successfully loaded to clipboard.");
1287  uint64_t loaded_image = display_image_load_srv.response.ir;
1288 
1289  display_image_paste_srv.request.ir = loaded_image;
1290  if (display_image_paste_client.call(display_image_paste_srv) && display_image_paste_srv.response.success == 1)
1291  ROS_INFO("Image successfully load and paste.");
1292  else
1293  ROS_ERROR("Failed to call service display_image_paste to paste image.");
1294 
1295  display_image_load_client.shutdown();
1296  time_step_client.call(time_step_srv);
1297 
1298  ros::ServiceClient display_image_delete_client;
1299  webots_ros::display_image_delete display_image_delete_srv;
1300  display_image_delete_client = n.serviceClient<webots_ros::display_image_delete>(model_name + "/display/image_delete");
1301 
1302  display_image_delete_srv.request.ir = loaded_image;
1303  if (display_image_delete_client.call(display_image_delete_srv) && display_image_delete_srv.response.success == 1)
1304  ROS_INFO("Loaded image has been deleted.");
1305  else
1306  ROS_ERROR("Failed to call service display_image_delete.");
1307 
1308  display_image_delete_srv.request.ir = copy_image;
1309  if (display_image_delete_client.call(display_image_delete_srv) && display_image_delete_srv.response.success == 1)
1310  ROS_INFO("Copy image has been deleted.");
1311  else
1312  ROS_ERROR("Failed to call service display_image_delete.");
1313 
1314  display_image_delete_srv.request.ir = new_image;
1315  if (display_image_delete_client.call(display_image_delete_srv) && display_image_delete_srv.response.success == 1)
1316  ROS_INFO("New image has been deleted.");
1317  else
1318  ROS_ERROR("Failed to call service display_image_delete.");
1319 
1320  display_image_delete_client.shutdown();
1321  time_step_client.call(time_step_srv);
1322 
1324  // DISTANCE SENSOR METHODS TEST //
1326 
1327  ros::ServiceClient set_distance_sensor_client;
1328  webots_ros::set_int distance_sensor_srv;
1329  ros::Subscriber sub_distance_sensor_32;
1330  set_distance_sensor_client = n.serviceClient<webots_ros::set_int>(model_name + "/distance_sensor/enable");
1331 
1332  ros::ServiceClient sampling_period_distance_sensor_client;
1333  webots_ros::get_int sampling_period_distance_sensor_srv;
1334  sampling_period_distance_sensor_client =
1335  n.serviceClient<webots_ros::get_int>(model_name + "/distance_sensor/get_sampling_period");
1336 
1337  ros::ServiceClient min_value_distance_sensor_client;
1338  webots_ros::get_float min_value_distance_sensor_srv;
1339  min_value_distance_sensor_client = n.serviceClient<webots_ros::get_float>(model_name + "/distance_sensor/get_min_value");
1340  if (min_value_distance_sensor_client.call(min_value_distance_sensor_srv))
1341  ROS_INFO("Distance_sensor min value = %g.", min_value_distance_sensor_srv.response.value);
1342  else
1343  ROS_ERROR("Failed to get the minimum value of 'distance_sensor'.");
1344  min_value_distance_sensor_client.shutdown();
1345 
1346  ros::ServiceClient max_value_distance_sensor_client;
1347  webots_ros::get_float max_value_distance_sensor_srv;
1348  max_value_distance_sensor_client = n.serviceClient<webots_ros::get_float>(model_name + "/distance_sensor/get_max_value");
1349  if (max_value_distance_sensor_client.call(max_value_distance_sensor_srv))
1350  ROS_INFO("Distance_sensor max value = %g.", max_value_distance_sensor_srv.response.value);
1351  else
1352  ROS_ERROR("Failed to get the maximum value of 'distance_sensor'.");
1353  max_value_distance_sensor_client.shutdown();
1354 
1355  ros::ServiceClient aperture_distance_sensor_client;
1356  webots_ros::get_float aperture_distance_sensor_srv;
1357  aperture_distance_sensor_client = n.serviceClient<webots_ros::get_float>(model_name + "/distance_sensor/get_aperture");
1358  if (aperture_distance_sensor_client.call(aperture_distance_sensor_srv))
1359  ROS_INFO("Distance_sensor aperture = %g.", aperture_distance_sensor_srv.response.value);
1360  else
1361  ROS_ERROR("Failed to get the aperture of 'distance_sensor'.");
1362  aperture_distance_sensor_client.shutdown();
1363 
1364  distance_sensor_srv.request.value = 32;
1365  if (set_distance_sensor_client.call(distance_sensor_srv) && distance_sensor_srv.response.success) {
1366  ROS_INFO("Distance_sensor enabled.");
1367  sub_distance_sensor_32 = n.subscribe(model_name + "/distance_sensor/value", 1, distance_sensorCallback);
1368  while (sub_distance_sensor_32.getNumPublishers() == 0) {
1369  ros::spinOnce();
1370  time_step_client.call(time_step_srv);
1371  }
1372  } else {
1373  if (!distance_sensor_srv.response.success)
1374  ROS_ERROR("Sampling period is not valid.");
1375  ROS_ERROR("Failed to enable distance_sensor.");
1376  return 1;
1377  }
1378 
1379  sub_distance_sensor_32.shutdown();
1380 
1381  time_step_client.call(time_step_srv);
1382 
1383  sampling_period_distance_sensor_client.call(sampling_period_distance_sensor_srv);
1384  ROS_INFO("Distance_sensor is enabled with a sampling period of %d.", sampling_period_distance_sensor_srv.response.value);
1385 
1386  time_step_client.call(time_step_srv);
1387 
1388  time_step_client.call(time_step_srv);
1389  time_step_client.call(time_step_srv);
1390  time_step_client.call(time_step_srv);
1391 
1392  sampling_period_distance_sensor_client.call(sampling_period_distance_sensor_srv);
1393  ROS_INFO("Distance_sensor is disabled (sampling period is %d).", sampling_period_distance_sensor_srv.response.value);
1394 
1395  set_distance_sensor_client.shutdown();
1396  sampling_period_distance_sensor_client.shutdown();
1397  time_step_client.call(time_step_srv);
1398 
1400  // EMITTER METHODS TEST //
1402 
1403  ros::ServiceClient emitter_send_client;
1404  webots_ros::set_string emitter_send_srv;
1405  emitter_send_client = n.serviceClient<webots_ros::set_string>(model_name + "/emitter/send");
1406 
1407  emitter_send_srv.request.value = "abc";
1408 
1409  if (emitter_send_client.call(emitter_send_srv) && emitter_send_srv.response.success)
1410  ROS_INFO("Emitter has sent data.");
1411  else
1412  ROS_ERROR("Failed to call service emitter_send to send data.");
1413 
1414  emitter_send_client.shutdown();
1415  time_step_client.call(time_step_srv);
1416 
1417  ros::ServiceClient emitter_get_buffer_size_client;
1418  webots_ros::get_int emitter_get_buffer_size_srv;
1419  emitter_get_buffer_size_client = n.serviceClient<webots_ros::get_int>(model_name + "/emitter/get_buffer_size");
1420 
1421  emitter_get_buffer_size_client.call(emitter_get_buffer_size_srv);
1422  ROS_INFO("Emitter's buffer is of size %d.", emitter_get_buffer_size_srv.response.value);
1423 
1424  emitter_get_buffer_size_client.shutdown();
1425  time_step_client.call(time_step_srv);
1426 
1427  ros::ServiceClient emitter_set_channel_client;
1428  webots_ros::set_int emitter_set_channel_srv;
1429  emitter_set_channel_client = n.serviceClient<webots_ros::set_int>(model_name + "/emitter/set_channel");
1430 
1431  emitter_set_channel_srv.request.value = 1;
1432 
1433  if (emitter_set_channel_client.call(emitter_set_channel_srv) && emitter_set_channel_srv.response.success)
1434  ROS_INFO("Emitter has update the channel.");
1435  else
1436  ROS_ERROR("Failed to call service emitter_set_channel to update channel.");
1437 
1438  emitter_set_channel_client.shutdown();
1439  time_step_client.call(time_step_srv);
1440 
1441  ros::ServiceClient emitter_set_range_client;
1442  webots_ros::set_float emitter_set_range_srv;
1443  emitter_set_range_client = n.serviceClient<webots_ros::set_float>(model_name + "/emitter/set_range");
1444 
1445  emitter_set_range_srv.request.value = 50;
1446 
1447  if (emitter_set_range_client.call(emitter_set_range_srv) && emitter_set_range_srv.response.success)
1448  ROS_INFO("Emitter has update the range.");
1449  else
1450  ROS_ERROR("Failed to call service emitter_set_range to update range.");
1451 
1452  emitter_set_range_client.shutdown();
1453  time_step_client.call(time_step_srv);
1454 
1455  ros::ServiceClient emitter_get_channel_client;
1456  webots_ros::get_int emitter_get_channel_srv;
1457  emitter_get_channel_client = n.serviceClient<webots_ros::get_int>(model_name + "/emitter/get_channel");
1458 
1459  emitter_get_channel_client.call(emitter_get_channel_srv);
1460  ROS_INFO("Emitter uses channel %d.", emitter_get_channel_srv.response.value);
1461 
1462  emitter_get_channel_client.shutdown();
1463  time_step_client.call(time_step_srv);
1464 
1465  ros::ServiceClient emitter_get_range_client;
1466  webots_ros::get_float emitter_get_range_srv;
1467  emitter_get_range_client = n.serviceClient<webots_ros::get_float>(model_name + "/emitter/get_range");
1468 
1469  emitter_get_range_client.call(emitter_get_range_srv);
1470  ROS_INFO("Emitter has a range of %f.", emitter_get_range_srv.response.value);
1471 
1472  emitter_get_range_client.shutdown();
1473  time_step_client.call(time_step_srv);
1474 
1476  // GPS METHODS TEST //
1478 
1479  ros::ServiceClient set_GPS_client;
1480  webots_ros::set_int GPS_srv;
1481  ros::Subscriber sub_GPS_32;
1482  ros::Subscriber sub_GPS_speed;
1483  set_GPS_client = n.serviceClient<webots_ros::set_int>(model_name + "/gps/enable");
1484 
1485  ros::ServiceClient sampling_period_GPS_client;
1486  webots_ros::get_int sampling_period_GPS_srv;
1487  sampling_period_GPS_client = n.serviceClient<webots_ros::get_int>(model_name + "/gps/get_sampling_period");
1488 
1489  GPS_srv.request.value = 32;
1490  if (set_GPS_client.call(GPS_srv) && GPS_srv.response.success) {
1491  ROS_INFO("GPS enabled.");
1492  sub_GPS_32 = n.subscribe(model_name + "/gps/values", 1, GPSCallback);
1493  while (sub_GPS_32.getNumPublishers() == 0) {
1494  ros::spinOnce();
1495  time_step_client.call(time_step_srv);
1496  }
1497  sub_GPS_32.shutdown();
1498  time_step_client.call(time_step_srv);
1499 
1500  sub_GPS_speed = n.subscribe(model_name + "/gps/speed", 1, GPSSpeedCallback);
1501  while (sub_GPS_speed.getNumPublishers() == 0) {
1502  ros::spinOnce();
1503  time_step_client.call(time_step_srv);
1504  }
1505  } else {
1506  if (!GPS_srv.response.success)
1507  ROS_ERROR("Sampling period is not valid.");
1508  ROS_ERROR("Failed to enable GPS.");
1509  return 1;
1510  }
1511 
1512  sub_GPS_speed.shutdown();
1513  time_step_client.call(time_step_srv);
1514 
1515  sampling_period_GPS_client.call(sampling_period_GPS_srv);
1516  ROS_INFO("GPS is enabled with a sampling period of %d.", sampling_period_GPS_srv.response.value);
1517 
1518  ros::ServiceClient gps_get_coordinate_system_client;
1519  webots_ros::get_int gps_get_coordinate_system_srv;
1520  gps_get_coordinate_system_client = n.serviceClient<webots_ros::get_int>(model_name + "/gps/get_coordinate_system");
1521 
1522  gps_get_coordinate_system_client.call(gps_get_coordinate_system_srv);
1523  ROS_INFO("GPS coordinate system type is: %d.", gps_get_coordinate_system_srv.response.value);
1524 
1525  time_step_client.call(time_step_srv);
1526 
1527  sampling_period_GPS_client.call(sampling_period_GPS_srv);
1528  ROS_INFO("GPS is disabled (sampling period is %d).", sampling_period_GPS_srv.response.value);
1529 
1530  set_GPS_client.shutdown();
1531  sampling_period_GPS_client.shutdown();
1532  gps_get_coordinate_system_client.shutdown();
1533  time_step_client.call(time_step_srv);
1534 
1536  // GYRO METHODS TEST //
1538 
1539  ros::ServiceClient set_gyro_client;
1540  webots_ros::set_int gyro_srv;
1541  ros::Subscriber sub_gyro_32;
1542  set_gyro_client = n.serviceClient<webots_ros::set_int>(model_name + "/gyro/enable");
1543 
1544  ros::ServiceClient sampling_period_gyro_client;
1545  webots_ros::get_int sampling_period_gyro_srv;
1546  sampling_period_gyro_client = n.serviceClient<webots_ros::get_int>(model_name + "/gyro/get_sampling_period");
1547 
1548  gyro_srv.request.value = 32;
1549  if (set_gyro_client.call(gyro_srv) && gyro_srv.response.success) {
1550  ROS_INFO("Gyro enabled.");
1551  sub_gyro_32 = n.subscribe(model_name + "/gyro/values", 1, gyroCallback);
1552  while (sub_gyro_32.getNumPublishers() == 0) {
1553  ros::spinOnce();
1554  time_step_client.call(time_step_srv);
1555  }
1556  } else {
1557  if (!gyro_srv.response.success)
1558  ROS_ERROR("Sampling period is not valid.");
1559  ROS_ERROR("Failed to enable gyro.");
1560  return 1;
1561  }
1562  sub_gyro_32.shutdown();
1563 
1564  time_step_client.call(time_step_srv);
1565 
1566  sampling_period_gyro_client.call(sampling_period_gyro_srv);
1567  ROS_INFO("Gyro is enabled with a sampling period of %d.", sampling_period_gyro_srv.response.value);
1568 
1569  time_step_client.call(time_step_srv);
1570 
1571  sampling_period_gyro_client.call(sampling_period_gyro_srv);
1572  ROS_INFO("Gyro is disabled (sampling period is %d).", sampling_period_gyro_srv.response.value);
1573 
1574  set_gyro_client.shutdown();
1575  sampling_period_gyro_client.shutdown();
1576  time_step_client.call(time_step_srv);
1577 
1579  // INERTIAL_UNIT METHODS TEST //
1581 
1582  ros::ServiceClient set_inertial_unit_client;
1583  webots_ros::set_int inertial_unit_srv;
1584  ros::Subscriber sub_inertial_unit_32;
1585  set_inertial_unit_client = n.serviceClient<webots_ros::set_int>(model_name + "/inertial_unit/enable");
1586 
1587  ros::ServiceClient sampling_period_inertial_unit_client;
1588  webots_ros::get_int sampling_period_inertial_unit_srv;
1589  sampling_period_inertial_unit_client =
1590  n.serviceClient<webots_ros::get_int>(model_name + "/inertial_unit/get_sampling_period");
1591 
1592  inertial_unit_srv.request.value = 32;
1593  if (set_inertial_unit_client.call(inertial_unit_srv) && inertial_unit_srv.response.success) {
1594  ROS_INFO("Inertial_unit enabled.");
1595  sub_inertial_unit_32 = n.subscribe(model_name + "/inertial_unit/roll_pitch_yaw", 1, inertialUnitCallback);
1596  while (sub_inertial_unit_32.getNumPublishers() == 0) {
1597  ros::spinOnce();
1598  time_step_client.call(time_step_srv);
1599  }
1600  } else {
1601  if (!inertial_unit_srv.response.success)
1602  ROS_ERROR("Sampling period is not valid.");
1603  ROS_ERROR("Failed to enable inertial_unit.");
1604  return 1;
1605  }
1606 
1607  sub_inertial_unit_32.shutdown();
1608 
1609  time_step_client.call(time_step_srv);
1610 
1611  sampling_period_inertial_unit_client.call(sampling_period_inertial_unit_srv);
1612  ROS_INFO("Inertial_unit is enabled with a sampling period of %d.", sampling_period_inertial_unit_srv.response.value);
1613 
1614  time_step_client.call(time_step_srv);
1615 
1616  sampling_period_inertial_unit_client.call(sampling_period_inertial_unit_srv);
1617  ROS_INFO("Inertial_unit is disabled (sampling period is %d).", sampling_period_inertial_unit_srv.response.value);
1618 
1619  set_inertial_unit_client.shutdown();
1620  sampling_period_inertial_unit_client.shutdown();
1621  time_step_client.call(time_step_srv);
1622 
1624  // JOYSTICK METHODS TEST //
1626 
1627  ros::ServiceClient enable_joystick_client = n.serviceClient<webots_ros::set_int>(model_name + "/joystick/enable");
1628  webots_ros::set_int enable_joystick_srv;
1629  ros::Subscriber sub_joystick;
1630 
1631  enable_joystick_srv.request.value = 32;
1632  if (enable_joystick_client.call(enable_joystick_srv) && enable_joystick_srv.response.success) {
1633  ROS_INFO("Joystick of %s has been enabled.", model_name.c_str());
1634  sub_joystick = n.subscribe(model_name + "/joystick/pressed_button", 1, joystickCallback);
1635  ROS_INFO("Topics for joystick initialized.");
1636 
1637  while (sub_joystick.getNumPublishers() == 0) {
1638  ros::spinOnce();
1639  time_step_client.call(time_step_srv);
1640  }
1641  ROS_INFO("Topics for joystick connected.");
1642  } else
1643  ROS_ERROR("Failed to enable joystick.");
1644 
1645  sub_joystick.shutdown();
1646 
1647  enable_joystick_client.shutdown();
1648  time_step_client.call(time_step_srv);
1649 
1650  ros::ServiceClient joystick_get_model_client;
1651  webots_ros::get_string joystick_get_model_srv;
1652  joystick_get_model_client = n.serviceClient<webots_ros::get_string>(model_name + "/joystick/get_model");
1653  joystick_get_model_client.call(joystick_get_model_srv);
1654  ROS_INFO("Got josytick model: %s.", joystick_get_model_srv.response.value.c_str());
1655 
1656  joystick_get_model_client.shutdown();
1657  time_step_client.call(time_step_srv);
1658 
1660  // LED METHODS TEST //
1662 
1663  ros::ServiceClient set_led_client;
1664  webots_ros::set_int set_led_srv;
1665  set_led_client = n.serviceClient<webots_ros::set_int>(model_name + "/led/set_led");
1666 
1667  set_led_srv.request.value = 1;
1668  if (set_led_client.call(set_led_srv) && set_led_srv.response.success)
1669  ROS_INFO("LED set to 1.");
1670  else
1671  ROS_ERROR("Failed to call service set_led.");
1672 
1673  enable_joystick_client.shutdown();
1674  set_led_client.call(time_step_srv);
1675 
1676  ros::ServiceClient get_led_client;
1677  webots_ros::get_int get_led_srv;
1678  get_led_client = n.serviceClient<webots_ros::get_int>(model_name + "/led/get_led");
1679 
1680  get_led_client.call(get_led_srv);
1681  ROS_INFO("LED value is %d.", get_led_srv.response.value);
1682 
1683  set_led_srv.request.value = 0;
1684  if (set_led_client.call(set_led_srv) && set_led_srv.response.success)
1685  ROS_INFO("LED set to 0.");
1686  else
1687  ROS_ERROR("Failed to call service set_led.");
1688 
1689  set_led_client.shutdown();
1690  get_led_client.shutdown();
1691  time_step_client.call(time_step_srv);
1692 
1694  // LIDAR METHODS TEST //
1696 
1697  // lidar enable
1698  ros::ServiceClient set_lidar_client;
1699  webots_ros::set_int lidar_srv;
1700  ros::Subscriber sub_lidar;
1701 
1702  set_lidar_client = n.serviceClient<webots_ros::set_int>(model_name + "/lidar/enable");
1703  lidar_srv.request.value = TIME_STEP;
1704  if (set_lidar_client.call(lidar_srv) && lidar_srv.response.success) {
1705  ROS_INFO("Lidar enabled.");
1706  sub_lidar = n.subscribe(model_name + "/lidar/range_image", 1, lidarCallback);
1707  ROS_INFO("Topic for lidar initialized.");
1708 
1709  while (sub_lidar.getNumPublishers() == 0) {
1710  ros::spinOnce();
1711  time_step_client.call(time_step_srv);
1712  }
1713  ROS_INFO("Topic for lidar color connected.");
1714  } else {
1715  if (!lidar_srv.response.success)
1716  ROS_ERROR("Sampling period is not valid.");
1717  ROS_ERROR("Failed to enable lidar.");
1718  return 1;
1719  }
1720 
1721  sub_lidar.shutdown();
1722  set_lidar_client.shutdown();
1723  time_step_client.call(time_step_srv);
1724 
1725  // lidar_get_info
1726  get_info_client = n.serviceClient<webots_ros::lidar_get_info>(model_name + "/lidar/get_info");
1727  webots_ros::lidar_get_info get_lidar_info_srv;
1728  if (get_info_client.call(get_lidar_info_srv))
1729  ROS_INFO("Lidar of %s has a horizontal resolution of %d, %d layers, a field of view of %f, a min range of %f and a max "
1730  "range of %f.",
1731  model_name.c_str(), get_lidar_info_srv.response.horizontalResolution, get_lidar_info_srv.response.numberOfLayers,
1732  get_lidar_info_srv.response.fov, get_lidar_info_srv.response.minRange, get_lidar_info_srv.response.maxRange);
1733  else
1734  ROS_ERROR("Failed to call service lidar_get_info.");
1735 
1736  get_info_client.shutdown();
1737  time_step_client.call(time_step_srv);
1738 
1739  // lidar_get_frequency_info
1740  get_info_client = n.serviceClient<webots_ros::lidar_get_frequency_info>(model_name + "/lidar/get_frequency_info");
1741  webots_ros::lidar_get_frequency_info get_lidar_frequency_info_srv;
1742  if (get_info_client.call(get_lidar_frequency_info_srv))
1743  ROS_INFO("Lidar %s current frequency is %f, maximum frequency is %f and minimum frequency is %f.", model_name.c_str(),
1744  get_lidar_frequency_info_srv.response.frequency, get_lidar_frequency_info_srv.response.maxFrequency,
1745  get_lidar_frequency_info_srv.response.minFrequency);
1746  else
1747  ROS_ERROR("Failed to call service lidar_get_frequency_info.");
1748 
1749  get_info_client.shutdown();
1750  time_step_client.call(time_step_srv);
1751 
1752  ROS_INFO("Lidar disabled.");
1753 
1755  // LIGHT SENSOR METHODS TEST //
1757 
1758  ros::ServiceClient set_light_sensor_client;
1759  webots_ros::set_int light_sensor_srv;
1760  ros::Subscriber sub_light_sensor_32;
1761  set_light_sensor_client = n.serviceClient<webots_ros::set_int>(model_name + "/light_sensor/enable");
1762 
1763  ros::ServiceClient sampling_period_light_sensor_client;
1764  webots_ros::get_int sampling_period_light_sensor_srv;
1765  sampling_period_light_sensor_client = n.serviceClient<webots_ros::get_int>(model_name + "/light_sensor/get_sampling_period");
1766 
1767  light_sensor_srv.request.value = 32;
1768  if (set_light_sensor_client.call(light_sensor_srv) && light_sensor_srv.response.success) {
1769  ROS_INFO("Light_sensor enabled.");
1770  sub_light_sensor_32 = n.subscribe(model_name + "/light_sensor/value", 1, lightSensorCallback);
1771  while (sub_light_sensor_32.getNumPublishers() == 0) {
1772  ros::spinOnce();
1773  time_step_client.call(time_step_srv);
1774  }
1775  } else {
1776  if (!light_sensor_srv.response.success)
1777  ROS_ERROR("Sampling period is not valid.");
1778  ROS_ERROR("Failed to enable light_sensor.");
1779  return 1;
1780  }
1781 
1782  sub_light_sensor_32.shutdown();
1783 
1784  time_step_client.call(time_step_srv);
1785 
1786  sampling_period_light_sensor_client.call(sampling_period_light_sensor_srv);
1787  ROS_INFO("Light_sensor is enabled with a sampling period of %d.", sampling_period_light_sensor_srv.response.value);
1788 
1789  time_step_client.call(time_step_srv);
1790 
1791  sampling_period_light_sensor_client.call(sampling_period_light_sensor_srv);
1792  ROS_INFO("Light_sensor is disabled (sampling period is %d).", sampling_period_light_sensor_srv.response.value);
1793 
1794  set_light_sensor_client.shutdown();
1795  sampling_period_light_sensor_client.shutdown();
1796  time_step_client.call(time_step_srv);
1797 
1799  // MOTOR METHODS TEST //
1801 
1802  ros::ServiceClient motor_get_type_client;
1803  webots_ros::get_int motor_get_type_srv;
1804  motor_get_type_client = n.serviceClient<webots_ros::get_int>(model_name + "/rotational_motor/get_type");
1805  motor_get_type_client.call(motor_get_type_srv);
1806  ROS_INFO("Rotational_motor is of type %d.", motor_get_type_srv.response.value);
1807 
1808  motor_get_type_client.shutdown();
1809  time_step_client.call(time_step_srv);
1810 
1811  ros::ServiceClient linear_motor_get_type_client;
1812  webots_ros::get_int linear_motor_get_type_srv;
1813  linear_motor_get_type_client = n.serviceClient<webots_ros::get_int>(model_name + "/linear_motor/get_type");
1814  linear_motor_get_type_client.call(linear_motor_get_type_srv);
1815  ROS_INFO("Linear_motor is of type %d.", linear_motor_get_type_srv.response.value);
1816 
1817  linear_motor_get_type_client.shutdown();
1818  time_step_client.call(time_step_srv);
1819 
1820  // motor_get_brake_name
1821  ros::ServiceClient motor_get_brake_name_client;
1822  webots_ros::get_string motor_get_brake_name_srv;
1823  motor_get_brake_name_client = n.serviceClient<webots_ros::get_string>(model_name + "/linear_motor/get_brake_name");
1824  if (motor_get_brake_name_client.call(motor_get_brake_name_srv)) {
1825  ROS_INFO("Brake name returned from Motor API: %s.", motor_get_brake_name_srv.response.value.c_str());
1826  if (motor_get_brake_name_srv.response.value.compare("my_brake") != 0)
1827  ROS_ERROR("Failed to call service motor_get_brake_name: received '%s' instead of 'my_brake'",
1828  motor_get_brake_name_srv.response.value.c_str());
1829  } else
1830  ROS_ERROR("Failed to call service motor_get_brake_name.");
1831 
1832  motor_get_brake_name_client.shutdown();
1833  time_step_client.call(time_step_srv);
1834 
1835  ros::ServiceClient set_acceleration_client;
1836  webots_ros::set_float set_acceleration_srv;
1837  set_acceleration_client = n.serviceClient<webots_ros::set_float>(model_name + "/rotational_motor/set_acceleration");
1838 
1839  set_acceleration_srv.request.value = 0.5;
1840  if (set_acceleration_client.call(set_acceleration_srv) && set_acceleration_srv.response.success)
1841  ROS_INFO("Acceleration set to 0.5.");
1842  else
1843  ROS_ERROR("Failed to call service set_acceleration on motor.");
1844 
1845  set_acceleration_client.shutdown();
1846  time_step_client.call(time_step_srv);
1847 
1848  ros::ServiceClient set_velocity_client;
1849  webots_ros::set_float set_velocity_srv;
1850  set_velocity_client = n.serviceClient<webots_ros::set_float>(model_name + "/rotational_motor/set_velocity");
1851 
1852  set_velocity_srv.request.value = 0.9;
1853  if (set_velocity_client.call(set_velocity_srv) && set_velocity_srv.response.success)
1854  ROS_INFO("Velocity set to 0.9.");
1855  else
1856  ROS_ERROR("Failed to call service set_velocity on motor.");
1857 
1858  set_velocity_client.shutdown();
1859  time_step_client.call(time_step_srv);
1860 
1861  ros::ServiceClient set_force_client;
1862  webots_ros::set_float set_force_srv;
1863  set_force_client = n.serviceClient<webots_ros::set_float>(model_name + "/linear_motor/set_force");
1864 
1865  set_force_srv.request.value = 0.2;
1866  if (set_force_client.call(set_force_srv) && set_force_srv.response.success)
1867  ROS_INFO("Force set to 0.2.");
1868  else
1869  ROS_ERROR("Failed to call service set_force on motor.");
1870 
1871  set_force_client.shutdown();
1872  time_step_client.call(time_step_srv);
1873 
1874  ros::ServiceClient set_torque_client;
1875  webots_ros::set_float set_torque_srv;
1876  set_torque_client = n.serviceClient<webots_ros::set_float>(model_name + "/rotational_motor/set_torque");
1877 
1878  set_torque_srv.request.value = 0.5;
1879  if (set_torque_client.call(set_torque_srv) && set_torque_srv.response.success)
1880  ROS_INFO("Torque set to 0.5.");
1881  else
1882  ROS_ERROR("Failed to call service set_torque on motor.");
1883 
1884  set_torque_client.shutdown();
1885  time_step_client.call(time_step_srv);
1886 
1887  ros::ServiceClient set_available_force_client;
1888  webots_ros::set_float set_available_force_srv;
1889  set_available_force_client = n.serviceClient<webots_ros::set_float>(model_name + "/linear_motor/set_available_force");
1890 
1891  set_available_force_srv.request.value = 0.8;
1892  if (set_available_force_client.call(set_available_force_srv) && set_available_force_srv.response.success)
1893  ROS_INFO("Available_force set to 0.8.");
1894  else
1895  ROS_ERROR("Failed to call service set_available_force on motor.");
1896 
1897  set_available_force_client.shutdown();
1898  time_step_client.call(time_step_srv);
1899 
1900  ros::ServiceClient set_available_torque_client;
1901  webots_ros::set_float set_available_torque_srv;
1902  set_available_torque_client = n.serviceClient<webots_ros::set_float>(model_name + "/rotational_motor/set_available_torque");
1903 
1904  set_available_torque_srv.request.value = 0.8;
1905  if (set_available_torque_client.call(set_available_torque_srv) && set_available_torque_srv.response.success)
1906  ROS_INFO("Available_torque set to 0.8.");
1907  else
1908  ROS_ERROR("Failed to call service set_available_torque on motor.");
1909 
1910  set_available_torque_client.shutdown();
1911  time_step_client.call(time_step_srv);
1912 
1913  ros::ServiceClient set_control_pid_client;
1914  webots_ros::motor_set_control_pid set_control_pid_srv;
1915  set_control_pid_client = n.serviceClient<webots_ros::motor_set_control_pid>(model_name + "/rotational_motor/set_control_pid");
1916 
1917  set_control_pid_srv.request.controlp = 1;
1918  if (set_control_pid_client.call(set_control_pid_srv) && set_control_pid_srv.response.success == 1)
1919  ROS_INFO("Control p set to 1.");
1920  else
1921  ROS_ERROR("Failed to call service set_controlp on motor.");
1922 
1923  set_control_pid_client.shutdown();
1924  time_step_client.call(time_step_srv);
1925  time_step_client.call(time_step_srv);
1926 
1927  ros::ServiceClient set_linear_control_pid_client;
1928  webots_ros::motor_set_control_pid set_linear_control_pid_srv;
1929  set_linear_control_pid_client =
1930  n.serviceClient<webots_ros::motor_set_control_pid>(model_name + "/linear_motor/set_control_pid");
1931 
1932  set_linear_control_pid_srv.request.controlp = 1;
1933  if (set_linear_control_pid_client.call(set_linear_control_pid_srv) && set_linear_control_pid_srv.response.success == 1)
1934  ROS_INFO("Control p set to 1 for linear_motor.");
1935  else
1936  ROS_ERROR("Failed to call service set_controlp on linear_motor.");
1937 
1938  set_linear_control_pid_client.shutdown();
1939  time_step_client.call(time_step_srv);
1940  time_step_client.call(time_step_srv);
1941 
1942  ros::ServiceClient set_position_client;
1943  webots_ros::set_float set_position_srv;
1944  set_position_client = n.serviceClient<webots_ros::set_float>(model_name + "/rotational_motor/set_position");
1945 
1946  set_position_srv.request.value = 1.5;
1947  if (set_position_client.call(set_position_srv) && set_position_srv.response.success)
1948  ROS_INFO("Position set to 1.5.");
1949  else
1950  ROS_ERROR("Failed to call service set_position on motor.");
1951 
1952  set_position_client.shutdown();
1953  time_step_client.call(time_step_srv);
1954  time_step_client.call(time_step_srv);
1955 
1956  ros::ServiceClient set_linear_position_client;
1957  webots_ros::set_float set_linear_position_srv;
1958  set_linear_position_client = n.serviceClient<webots_ros::set_float>(model_name + "/linear_motor/set_position");
1959 
1960  set_linear_position_srv.request.value = 0.3;
1961  if (set_linear_position_client.call(set_linear_position_srv) && set_linear_position_srv.response.success)
1962  ROS_INFO("Position set to 0.3 for linear_motor.");
1963  else
1964  ROS_ERROR("Failed to call service set_position on linear_motor.");
1965 
1966  set_linear_position_client.shutdown();
1967  time_step_client.call(time_step_srv);
1968 
1969  ros::ServiceClient get_target_position_client;
1970  webots_ros::get_float get_target_position_srv;
1971  get_target_position_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_target_position");
1972 
1973  get_target_position_client.call(get_target_position_srv);
1974  ROS_INFO("Target position for rotational_motor is %f.", get_target_position_srv.response.value);
1975 
1976  get_target_position_client.shutdown();
1977  time_step_client.call(time_step_srv);
1978 
1979  ros::ServiceClient get_min_position_client;
1980  webots_ros::get_float get_min_position_srv;
1981  get_min_position_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_min_position");
1982 
1983  get_min_position_client.call(get_min_position_srv);
1984  ROS_INFO("Min position for rotational_motor is %f.", get_min_position_srv.response.value);
1985 
1986  get_min_position_client.shutdown();
1987  time_step_client.call(time_step_srv);
1988 
1989  ros::ServiceClient get_max_position_client;
1990  webots_ros::get_float get_max_position_srv;
1991  get_max_position_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_max_position");
1992 
1993  get_max_position_client.call(get_max_position_srv);
1994  ROS_INFO("Max position for rotational_motor is %f.", get_max_position_srv.response.value);
1995 
1996  get_max_position_client.shutdown();
1997  time_step_client.call(time_step_srv);
1998 
1999  ros::ServiceClient get_velocity_client;
2000  webots_ros::get_float get_velocity_srv;
2001  get_velocity_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_velocity");
2002 
2003  get_velocity_client.call(get_velocity_srv);
2004  ROS_INFO("Velocity for rotational_motor is %f.", get_velocity_srv.response.value);
2005 
2006  get_velocity_client.shutdown();
2007  time_step_client.call(time_step_srv);
2008 
2009  ros::ServiceClient get_max_velocity_client;
2010  webots_ros::get_float get_max_velocity_srv;
2011  get_max_velocity_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_max_velocity");
2012 
2013  get_max_velocity_client.call(get_max_velocity_srv);
2014  ROS_INFO("Max velocity for rotational_motor is %f.", get_max_velocity_srv.response.value);
2015 
2016  get_max_velocity_client.shutdown();
2017  time_step_client.call(time_step_srv);
2018 
2019  ros::ServiceClient get_acceleration_client;
2020  webots_ros::get_float get_acceleration_srv;
2021  get_acceleration_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_acceleration");
2022 
2023  get_acceleration_client.call(get_acceleration_srv);
2024  ROS_INFO("Acceleration for rotational_motor is %f.", get_acceleration_srv.response.value);
2025 
2026  get_acceleration_client.shutdown();
2027  time_step_client.call(time_step_srv);
2028 
2029  ros::ServiceClient get_available_force_client;
2030  webots_ros::get_float get_available_force_srv;
2031  get_available_force_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_available_force");
2032 
2033  get_available_force_client.call(get_available_force_srv);
2034  ROS_INFO("Available force for rotational_motor is %f.", get_available_force_srv.response.value);
2035 
2036  get_available_force_client.shutdown();
2037  time_step_client.call(time_step_srv);
2038 
2039  ros::ServiceClient get_max_force_client;
2040  webots_ros::get_float get_max_force_srv;
2041  get_max_force_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_max_force");
2042 
2043  get_max_force_client.call(get_max_force_srv);
2044  ROS_INFO("Max force for rotational_motor is %f.", get_max_force_srv.response.value);
2045 
2046  get_max_force_client.shutdown();
2047  time_step_client.call(time_step_srv);
2048 
2049  ros::ServiceClient get_available_torque_client;
2050  webots_ros::get_float get_available_torque_srv;
2051  get_available_torque_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_available_torque");
2052 
2053  get_available_torque_client.call(get_available_torque_srv);
2054  ROS_INFO("Available torque for rotational_motor is %f.", get_available_torque_srv.response.value);
2055 
2056  get_available_torque_client.shutdown();
2057  time_step_client.call(time_step_srv);
2058 
2059  ros::ServiceClient get_max_torque_client;
2060  webots_ros::get_float get_max_torque_srv;
2061  get_max_torque_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_max_torque");
2062 
2063  get_max_torque_client.call(get_max_torque_srv);
2064  ROS_INFO("Max torque for rotational_motor is %f.", get_max_torque_srv.response.value);
2065 
2066  get_max_torque_client.shutdown();
2067  time_step_client.call(time_step_srv);
2068  time_step_client.call(time_step_srv);
2069 
2071  // PEN METHODS TEST //
2073 
2074  ros::ServiceClient set_ink_color_client;
2075  webots_ros::pen_set_ink_color set_ink_color_srv;
2076  set_ink_color_client = n.serviceClient<webots_ros::pen_set_ink_color>(model_name + "/pen/set_ink_color");
2077 
2078  set_ink_color_srv.request.color = 0x00FF08;
2079  if (set_ink_color_client.call(set_ink_color_srv) && set_ink_color_srv.response.success == 1)
2080  ROS_INFO("Ink color set to turquoise.");
2081  else
2082  ROS_ERROR("Failed to call service set_ink_color.");
2083 
2084  set_ink_color_client.shutdown();
2085  time_step_client.call(time_step_srv);
2086 
2087  ros::ServiceClient pen_write_client;
2088  webots_ros::set_bool pen_write_srv;
2089  pen_write_client = n.serviceClient<webots_ros::set_bool>(model_name + "/pen/write");
2090 
2091  pen_write_srv.request.value = true;
2092  if (pen_write_client.call(pen_write_srv) && pen_write_srv.response.success)
2093  ROS_INFO("Pen is now writing.");
2094  else
2095  ROS_ERROR("Failed to call service pen_write.");
2096 
2097  pen_write_client.shutdown();
2098  time_step_client.call(time_step_srv);
2099  time_step_client.call(time_step_srv);
2100 
2102  // POSITION SENSOR METHODS TEST //
2104 
2105  ros::ServiceClient set_position_sensor_client;
2106  webots_ros::set_int position_sensor_srv;
2107  ros::Subscriber sub_position_sensor_32;
2108  set_position_sensor_client = n.serviceClient<webots_ros::set_int>(model_name + "/position_sensor/enable");
2109 
2110  ros::ServiceClient sampling_period_position_sensor_client;
2111  webots_ros::get_int sampling_period_position_sensor_srv;
2112  sampling_period_position_sensor_client =
2113  n.serviceClient<webots_ros::get_int>(model_name + "/position_sensor/get_sampling_period");
2114 
2115  position_sensor_srv.request.value = 32;
2116  if (set_position_sensor_client.call(position_sensor_srv) && position_sensor_srv.response.success) {
2117  ROS_INFO("Position_sensor enabled.");
2118  sub_position_sensor_32 = n.subscribe(model_name + "/position_sensor/value", 1, positionSensorCallback);
2119  while (sub_position_sensor_32.getNumPublishers() == 0) {
2120  ros::spinOnce();
2121  time_step_client.call(time_step_srv);
2122  }
2123  } else {
2124  if (!position_sensor_srv.response.success)
2125  ROS_ERROR("Sampling period is not valid.");
2126  ROS_ERROR("Failed to enable position_sensor.");
2127  return 1;
2128  }
2129 
2130  sub_position_sensor_32.shutdown();
2131 
2132  time_step_client.call(time_step_srv);
2133 
2134  sampling_period_position_sensor_client.call(sampling_period_position_sensor_srv);
2135  ROS_INFO("Position_sensor is enabled with a sampling period of %d.", sampling_period_position_sensor_srv.response.value);
2136 
2137  time_step_client.call(time_step_srv);
2138 
2139  ros::ServiceClient position_sensor_get_type_client;
2140  webots_ros::get_int position_sensor_get_type_srv;
2141  position_sensor_get_type_client = n.serviceClient<webots_ros::get_int>(model_name + "/position_sensor/get_type");
2142 
2143  position_sensor_get_type_client.call(position_sensor_get_type_srv);
2144  ROS_INFO("Position_sensor is of type %d.", position_sensor_get_type_srv.response.value);
2145 
2146  position_sensor_get_type_client.shutdown();
2147  time_step_client.call(time_step_srv);
2148 
2149  sampling_period_position_sensor_client.call(sampling_period_position_sensor_srv);
2150  ROS_INFO("Position_sensor is disabled (sampling period is %d).", sampling_period_position_sensor_srv.response.value);
2151 
2152  set_position_sensor_client.shutdown();
2153  sampling_period_position_sensor_client.shutdown();
2154  time_step_client.call(time_step_srv);
2155 
2157  // RADAR METHODS TEST //
2159 
2160  // radar enable
2161  ros::ServiceClient set_radar_client;
2162  webots_ros::set_int radar_srv;
2163  ros::Subscriber sub_radar_target;
2164  ros::Subscriber sub_radar_target_number;
2165 
2166  set_radar_client = n.serviceClient<webots_ros::set_int>(model_name + "/radar/enable");
2167  radar_srv.request.value = TIME_STEP;
2168  if (set_radar_client.call(radar_srv) && radar_srv.response.success) {
2169  ROS_INFO("Radar enabled.");
2170  sub_radar_target = n.subscribe(model_name + "/radar/targets", 1, radarTargetsCallback);
2171  sub_radar_target_number = n.subscribe(model_name + "/radar/number_of_targets", 1, radarTargetsNumberCallback);
2172  ROS_INFO("Topics for radar initialized.");
2173 
2174  while (sub_radar_target.getNumPublishers() == 0 && sub_radar_target_number.getNumPublishers() == 0) {
2175  ros::spinOnce();
2176  time_step_client.call(time_step_srv);
2177  }
2178  ROS_INFO("Topics for radar connected.");
2179  } else {
2180  if (!radar_srv.response.success)
2181  ROS_ERROR("Sampling period is not valid.");
2182  ROS_ERROR("Failed to enable radar.");
2183  return 1;
2184  }
2185 
2186  sub_radar_target.shutdown();
2187  sub_radar_target_number.shutdown();
2188  set_radar_client.shutdown();
2189  time_step_client.call(time_step_srv);
2190 
2191  // get max and min range
2192  ros::ServiceClient radar_range_client = n.serviceClient<webots_ros::get_float>(model_name + "/radar/get_max_range");
2193  webots_ros::get_float radar_get_max_range_srv;
2194  if (radar_range_client.call(radar_get_max_range_srv)) {
2195  if (radar_get_max_range_srv.response.value == 2.0)
2196  ROS_INFO("Received correct radar max range.");
2197  else
2198  ROS_ERROR("Received wrong radar max range.");
2199  } else
2200  ROS_ERROR("Failed to call service radar_get_max_range.");
2201 
2202  radar_range_client.shutdown();
2203  time_step_client.call(time_step_srv);
2204 
2205  radar_range_client = n.serviceClient<webots_ros::get_float>(model_name + "/radar/get_min_range");
2206  webots_ros::get_float radar_get_min_range_srv;
2207  if (radar_range_client.call(radar_get_min_range_srv)) {
2208  if (radar_get_min_range_srv.response.value == 1.0)
2209  ROS_INFO("Received correct radar min range.");
2210  else
2211  ROS_ERROR("Received wrong radar min range.");
2212  } else
2213  ROS_ERROR("Failed to call service radar_get_min_range.");
2214 
2215  radar_range_client.shutdown();
2216  time_step_client.call(time_step_srv);
2217 
2218  ROS_INFO("Radar disabled.");
2219 
2221  // RANGE-FINDER METHODS TEST //
2223 
2224  // range-finder enable
2225  ros::ServiceClient set_range_finder_client;
2226  webots_ros::set_int range_finder_srv;
2227  ros::Subscriber sub_range_finder_color;
2228 
2229  set_range_finder_client = n.serviceClient<webots_ros::set_int>(model_name + "/range_finder/enable");
2230  range_finder_srv.request.value = TIME_STEP;
2231  if (set_range_finder_client.call(range_finder_srv) && range_finder_srv.response.success) {
2232  ROS_INFO("Range-finder enabled.");
2233  sub_range_finder_color = n.subscribe(model_name + "/range_finder/range_image", 1, rangeFinderCallback);
2234  ROS_INFO("Topic for range-finder initialized.");
2235 
2236  while (sub_range_finder_color.getNumPublishers() == 0) {
2237  ros::spinOnce();
2238  time_step_client.call(time_step_srv);
2239  }
2240  ROS_INFO("Topic for range-finder connected.");
2241  } else {
2242  if (!range_finder_srv.response.success)
2243  ROS_ERROR("Sampling period is not valid.");
2244  ROS_ERROR("Failed to enable range-finder.");
2245  return 1;
2246  }
2247 
2248  sub_range_finder_color.shutdown();
2249  set_range_finder_client.shutdown();
2250  time_step_client.call(time_step_srv);
2251 
2252  // range_finder_get_info
2253  get_info_client = n.serviceClient<webots_ros::range_finder_get_info>(model_name + "/range_finder/get_info");
2254  webots_ros::range_finder_get_info get_range_finder_info_srv;
2255  if (get_info_client.call(get_range_finder_info_srv))
2256  ROS_INFO(
2257  "Range-finder of %s has a width of %d, a height of %d, a field of view of %f, a min range of %f and a max range of %f.",
2258  model_name.c_str(), get_range_finder_info_srv.response.width, get_range_finder_info_srv.response.height,
2259  get_range_finder_info_srv.response.Fov, get_range_finder_info_srv.response.minRange,
2260  get_range_finder_info_srv.response.maxRange);
2261  else
2262  ROS_ERROR("Failed to call service range_finder_get_info.");
2263 
2264  get_info_client.shutdown();
2265  time_step_client.call(time_step_srv);
2266 
2267  // range_finder_save_image
2268  save_image_client = n.serviceClient<webots_ros::save_image>(model_name + "/range_finder/save_image");
2269  webots_ros::save_image save_range_image_srv;
2270  save_range_image_srv.request.filename = std::string(getenv("HOME")) + std::string("/test_image_range_finder.png");
2271  save_range_image_srv.request.quality = 100;
2272 
2273  if (save_image_client.call(save_range_image_srv) && save_range_image_srv.response.success == 1)
2274  ROS_INFO("Image saved.");
2275  else
2276  ROS_ERROR("Failed to call service save_image.");
2277 
2278  save_image_client.shutdown();
2279  time_step_client.call(time_step_srv);
2280 
2281  ROS_INFO("Range-finder disabled.");
2282 
2284  // RECEIVER METHODS TEST //
2286 
2287  ros::ServiceClient set_receiver_client;
2288  webots_ros::set_int receiver_srv;
2289  ros::Subscriber sub_receiver_32;
2290  set_receiver_client = n.serviceClient<webots_ros::set_int>(model_name + "/receiver/enable");
2291 
2292  ros::ServiceClient sampling_period_receiver_client;
2293  webots_ros::get_int sampling_period_receiver_srv;
2294  sampling_period_receiver_client = n.serviceClient<webots_ros::get_int>(model_name + "/receiver/get_sampling_period");
2295 
2296  receiver_srv.request.value = 32;
2297  if (set_receiver_client.call(receiver_srv) && receiver_srv.response.success) {
2298  ROS_INFO("Receiver enabled.");
2299  sub_receiver_32 = n.subscribe(model_name + "/receiver/data", 1, receiverCallback);
2300  while (sub_receiver_32.getNumPublishers() == 0) {
2301  ros::spinOnce();
2302  time_step_client.call(time_step_srv);
2303  }
2304  } else {
2305  if (!receiver_srv.response.success)
2306  ROS_ERROR("Sampling period is not valid.");
2307  ROS_ERROR("Failed to enable receiver.");
2308  return 1;
2309  }
2310 
2311  sub_receiver_32.shutdown();
2312  set_receiver_client.shutdown();
2313  time_step_client.call(time_step_srv);
2314 
2315  sampling_period_receiver_client.call(sampling_period_receiver_srv);
2316  ROS_INFO("Receiver is enabled with a sampling period of %d.", sampling_period_receiver_srv.response.value);
2317 
2318  time_step_client.call(time_step_srv);
2319  time_step_client.call(time_step_srv);
2320 
2321  // test receiver_get_data_size
2322  // An error message will probably appear since no data has been sent to the receiver.
2323  ros::ServiceClient receiver_get_data_size_client;
2324  webots_ros::get_int receiver_get_data_size_srv;
2325  receiver_get_data_size_client = n.serviceClient<webots_ros::get_int>(model_name + "/receiver/get_data_size");
2326 
2327  receiver_get_data_size_client.call(receiver_get_data_size_srv);
2328  if (receiver_get_data_size_srv.response.value != -1)
2329  ROS_INFO("Emitter's buffer is of size %d.", receiver_get_data_size_srv.response.value);
2330  else
2331  ROS_INFO("No message received by emitter, impossible to get buffer size.");
2332 
2333  receiver_get_data_size_client.shutdown();
2334  time_step_client.call(time_step_srv);
2335  time_step_client.call(time_step_srv);
2336 
2337  ros::ServiceClient receiver_set_channel_client;
2338  webots_ros::set_int receiver_set_channel_srv;
2339  receiver_set_channel_client = n.serviceClient<webots_ros::set_int>(model_name + "/receiver/set_channel");
2340 
2341  receiver_set_channel_srv.request.value = 1;
2342 
2343  if (receiver_set_channel_client.call(receiver_set_channel_srv) && receiver_set_channel_srv.response.success)
2344  ROS_INFO("Receiver has update the channel.");
2345  else
2346  ROS_ERROR("Failed to call service receiver_set_channel to update channel.");
2347 
2348  receiver_set_channel_client.shutdown();
2349  time_step_client.call(time_step_srv);
2350 
2351  // test receiver_get_channel
2352  ros::ServiceClient receiver_get_channel_client;
2353  webots_ros::get_int receiver_get_channel_srv;
2354  receiver_get_channel_client = n.serviceClient<webots_ros::get_int>(model_name + "/receiver/get_channel");
2355 
2356  receiver_get_channel_client.call(receiver_get_channel_srv);
2357  ROS_INFO("Receiver uses channel %d.", receiver_get_channel_srv.response.value);
2358 
2359  receiver_get_channel_client.shutdown();
2360  time_step_client.call(time_step_srv);
2361 
2362  // test receiver_get_queue_length
2363  ros::ServiceClient receiver_get_queue_length_client;
2364  webots_ros::get_int receiver_get_queue_length_srv;
2365  receiver_get_queue_length_client = n.serviceClient<webots_ros::get_int>(model_name + "/receiver/get_queue_length");
2366 
2367  receiver_get_queue_length_client.call(receiver_get_queue_length_srv);
2368  ROS_INFO("Length of receiver queue is %d.", receiver_get_queue_length_srv.response.value);
2369 
2370  receiver_get_queue_length_client.shutdown();
2371  time_step_client.call(time_step_srv);
2372 
2373  // test receiver_get_signal_strength
2374  // An error message will probably appear since no signal has been sent to the receiver.
2375  ros::ServiceClient receiver_get_signal_strength_client;
2376  webots_ros::get_float receiver_get_signal_strength_srv;
2377  receiver_get_signal_strength_client = n.serviceClient<webots_ros::get_float>(model_name + "/receiver/get_signal_strength");
2378 
2379  receiver_get_signal_strength_client.call(receiver_get_signal_strength_srv);
2380  if (receiver_get_signal_strength_srv.response.value != -1.0)
2381  ROS_INFO("Strength of the signal is %lf.", receiver_get_signal_strength_srv.response.value);
2382  else
2383  ROS_INFO("No message received by emitter, impossible to get signal strength.");
2384 
2385  receiver_get_signal_strength_client.shutdown();
2386  time_step_client.call(time_step_srv);
2387 
2388  // test receiver_get_emitter_direction
2389  // An error message will probably appear since no signal has been sent to the receiver
2390  ros::ServiceClient receiver_get_emitter_direction_client;
2391  webots_ros::receiver_get_emitter_direction receiver_get_emitter_direction_srv;
2392  receiver_get_emitter_direction_client =
2393  n.serviceClient<webots_ros::receiver_get_emitter_direction>(model_name + "/receiver/get_emitter_direction");
2394 
2395  receiver_get_emitter_direction_client.call(receiver_get_emitter_direction_srv);
2396  if (receiver_get_emitter_direction_srv.response.direction[0] != 0 ||
2397  receiver_get_emitter_direction_srv.response.direction[1] != 0 ||
2398  receiver_get_emitter_direction_srv.response.direction[2] != 0)
2399  ROS_INFO("Signal from emitter comes from direction {%f. %f, %f}.", receiver_get_emitter_direction_srv.response.direction[0],
2400  receiver_get_emitter_direction_srv.response.direction[1],
2401  receiver_get_emitter_direction_srv.response.direction[2]);
2402  else
2403  ROS_INFO("No message received by emitter, impossible to get signal direction.");
2404 
2405  receiver_get_emitter_direction_client.shutdown();
2406  time_step_client.call(time_step_srv);
2407 
2408  // test receiver_next_packet
2409  // An error message will probably appear since there is no packet to read
2410  ros::ServiceClient receiver_next_packet_client;
2411  webots_ros::get_bool receiver_next_packet_srv;
2412  receiver_next_packet_client = n.serviceClient<webots_ros::get_bool>(model_name + "/receiver/next_packet");
2413 
2414  if (receiver_next_packet_client.call(receiver_next_packet_srv) && receiver_next_packet_srv.response.value)
2415  ROS_INFO("Next packet is ready to be read.");
2416  else if (!receiver_next_packet_srv.response.value)
2417  ROS_INFO("No message received by emitter, impossible to get next packet.");
2418  else
2419  ROS_ERROR("Failed to call service receiver_next_packet.");
2420 
2421  receiver_next_packet_client.shutdown();
2422  time_step_client.call(time_step_srv);
2423 
2424  sampling_period_receiver_client.call(sampling_period_receiver_srv);
2425  ROS_INFO("Receiver is disabled (sampling period is %d).", sampling_period_receiver_srv.response.value);
2426 
2427  sampling_period_receiver_client.shutdown();
2428  time_step_client.call(time_step_srv);
2429 
2431  // TOUCH SENSOR METHODS TEST //
2433 
2434  ros::ServiceClient set_touch_sensor_client;
2435  webots_ros::set_int touch_sensor_srv;
2436  ros::Subscriber sub_touch_sensor_32;
2437  set_touch_sensor_client = n.serviceClient<webots_ros::set_int>(model_name + "/touch_sensor/enable");
2438 
2439  ros::ServiceClient sampling_period_touch_sensor_client;
2440  webots_ros::get_int sampling_period_touch_sensor_srv;
2441  sampling_period_touch_sensor_client = n.serviceClient<webots_ros::get_int>(model_name + "/touch_sensor/get_sampling_period");
2442 
2443  ros::ServiceClient touch_sensor_get_type_client;
2444  webots_ros::get_int touch_sensor_get_type_srv;
2445  touch_sensor_get_type_client = n.serviceClient<webots_ros::get_int>(model_name + "/touch_sensor/get_type");
2446 
2447  touch_sensor_get_type_client.call(touch_sensor_get_type_srv);
2448  ROS_INFO("Touch_sensor is of type %d.", touch_sensor_get_type_srv.response.value);
2449 
2450  touch_sensor_get_type_client.shutdown();
2451  time_step_client.call(time_step_srv);
2452 
2453  touch_sensor_srv.request.value = 32;
2454  if (set_touch_sensor_client.call(touch_sensor_srv) && touch_sensor_srv.response.success) {
2455  ROS_INFO("Touch_sensor enabled.");
2456  if (touch_sensor_get_type_srv.response.value == 0)
2457  sub_touch_sensor_32 = n.subscribe(model_name + "/touch_sensor/value", 1, touchSensorBumperCallback);
2458  else if (touch_sensor_get_type_srv.response.value == 1)
2459  sub_touch_sensor_32 = n.subscribe(model_name + "/touch_sensor/value", 1, touchSensorCallback);
2460  else
2461  sub_touch_sensor_32 = n.subscribe(model_name + "/touch_sensor/values", 1, touchSensor3DCallback);
2462  while (sub_touch_sensor_32.getNumPublishers() == 0) {
2463  ros::spinOnce();
2464  time_step_client.call(time_step_srv);
2465  }
2466  } else {
2467  if (!touch_sensor_srv.response.success)
2468  ROS_ERROR("Sampling period is not valid.");
2469  ROS_ERROR("Failed to enable touch_sensor.");
2470  return 1;
2471  }
2472 
2473  sub_touch_sensor_32.shutdown();
2474 
2475  time_step_client.call(time_step_srv);
2476 
2477  sampling_period_touch_sensor_client.call(sampling_period_touch_sensor_srv);
2478  ROS_INFO("Touch_sensor is enabled with a sampling period of %d.", sampling_period_touch_sensor_srv.response.value);
2479 
2480  time_step_client.call(time_step_srv);
2481 
2482  sampling_period_touch_sensor_client.call(sampling_period_touch_sensor_srv);
2483  ROS_INFO("Touch_sensor is disabled (sampling period is %d).", sampling_period_touch_sensor_srv.response.value);
2484 
2485  set_touch_sensor_client.shutdown();
2486  sampling_period_touch_sensor_client.shutdown();
2487  time_step_client.call(time_step_srv);
2488 
2490  // SUPERVISOR METHODS TEST //
2492 
2493  ros::ServiceClient supervisor_simulation_reset_physics_client;
2494  webots_ros::get_bool supervisor_simulation_reset_physics_srv;
2495  supervisor_simulation_reset_physics_client =
2496  n.serviceClient<webots_ros::get_bool>(model_name + "/supervisor/simulation_reset_physics");
2497 
2498  if (supervisor_simulation_reset_physics_client.call(supervisor_simulation_reset_physics_srv) &&
2499  supervisor_simulation_reset_physics_srv.response.value)
2500  ROS_INFO("Simulation has reset_physics successfully.");
2501  else
2502  ROS_ERROR("Failed to call service simulation_reset_physics.");
2503 
2504  supervisor_simulation_reset_physics_client.shutdown();
2505  time_step_client.call(time_step_srv);
2506 
2507  ros::ServiceClient supervisor_export_image_client;
2508  webots_ros::save_image supervisor_export_image_srv;
2509  supervisor_export_image_client = n.serviceClient<webots_ros::save_image>(model_name + "/supervisor/export_image");
2510 
2511  supervisor_export_image_srv.request.filename = std::string(getenv("HOME")) + std::string("/main_window_test.jpg");
2512  supervisor_export_image_srv.request.quality = 100;
2513  if (supervisor_export_image_client.call(supervisor_export_image_srv) && supervisor_export_image_srv.response.success == 1)
2514  ROS_INFO("Image from main window saved successfully.");
2515  else
2516  ROS_ERROR("Failed to call service export_image.");
2517 
2518  supervisor_export_image_client.shutdown();
2519  time_step_client.call(time_step_srv);
2520 
2521  ros::ServiceClient supervisor_set_label_client;
2522  webots_ros::supervisor_set_label supervisor_set_label_srv;
2523  supervisor_set_label_client = n.serviceClient<webots_ros::supervisor_set_label>(model_name + "/supervisor/set_label");
2524 
2525  supervisor_set_label_srv.request.id = 1;
2526  supervisor_set_label_srv.request.label = "This is a label";
2527  supervisor_set_label_srv.request.xpos = 0.02;
2528  supervisor_set_label_srv.request.ypos = 0.2;
2529  supervisor_set_label_srv.request.size = 0.1;
2530  supervisor_set_label_srv.request.color = 0XFF0000;
2531  supervisor_set_label_srv.request.transparency = 0;
2532  supervisor_set_label_srv.request.font = "Lucida Console";
2533  if (supervisor_set_label_client.call(supervisor_set_label_srv) && supervisor_set_label_srv.response.success == 1)
2534  ROS_INFO("Label set successfully.");
2535  else
2536  ROS_ERROR("Failed to call service set_label.");
2537 
2538  time_step_client.call(time_step_srv);
2539 
2540  ros::ServiceClient supervisor_get_root_client;
2541  webots_ros::get_uint64 supervisor_get_root_srv;
2542  supervisor_get_root_client = n.serviceClient<webots_ros::get_uint64>(model_name + "/supervisor/get_root");
2543 
2544  supervisor_get_root_client.call(supervisor_get_root_srv);
2545  ROS_INFO("Got root node: %lu.", supervisor_get_root_srv.response.value);
2546  uint64_t root_node = supervisor_get_root_srv.response.value;
2547 
2548  supervisor_get_root_client.shutdown();
2549  time_step_client.call(time_step_srv);
2550 
2551  ros::ServiceClient supervisor_get_self_client;
2552  webots_ros::get_uint64 supervisor_get_self_srv;
2553  supervisor_get_self_client = n.serviceClient<webots_ros::get_uint64>(model_name + "/supervisor/get_self");
2554 
2555  supervisor_get_self_client.call(supervisor_get_self_srv);
2556  ROS_INFO("Got self node: %lu.", supervisor_get_self_srv.response.value);
2557  uint64_t self_node = supervisor_get_self_srv.response.value;
2558 
2559  supervisor_get_self_client.shutdown();
2560  time_step_client.call(time_step_srv);
2561 
2562  ros::ServiceClient supervisor_get_from_def_client;
2563  webots_ros::supervisor_get_from_def supervisor_get_from_def_srv;
2564  supervisor_get_from_def_client =
2565  n.serviceClient<webots_ros::supervisor_get_from_def>(model_name + "/supervisor/get_from_def");
2566 
2567  supervisor_get_from_def_srv.request.name = "TEST";
2568  supervisor_get_from_def_client.call(supervisor_get_from_def_srv);
2569  uint64_t from_def_node = 0;
2570  if (supervisor_get_from_def_srv.response.node != 0) {
2571  ROS_INFO("Got from DEF node: %ld.", supervisor_get_from_def_srv.response.node);
2572  from_def_node = supervisor_get_from_def_srv.response.node;
2573  } else
2574  ROS_ERROR("Could not get node from DEF.");
2575 
2576  time_step_client.call(time_step_srv);
2577 
2578  ros::ServiceClient supervisor_node_get_type_client;
2579  webots_ros::node_get_type supervisor_node_get_type_srv;
2580  supervisor_node_get_type_client = n.serviceClient<webots_ros::node_get_type>(model_name + "/supervisor/node/get_type");
2581 
2582  supervisor_node_get_type_srv.request.node = from_def_node;
2583  supervisor_node_get_type_client.call(supervisor_node_get_type_srv);
2584  ROS_INFO("Got node type: %d.", supervisor_node_get_type_srv.response.type);
2585 
2586  supervisor_node_get_type_client.shutdown();
2587  time_step_client.call(time_step_srv);
2588 
2589  ros::ServiceClient supervisor_node_get_type_name_client;
2590  webots_ros::node_get_name supervisor_node_get_type_name_srv;
2591  supervisor_node_get_type_name_client =
2592  n.serviceClient<webots_ros::node_get_name>(model_name + "/supervisor/node/get_type_name");
2593 
2594  supervisor_node_get_type_name_srv.request.node = from_def_node;
2595  supervisor_node_get_type_name_client.call(supervisor_node_get_type_name_srv);
2596  ROS_INFO("Got node type name: %s.", supervisor_node_get_type_name_srv.response.name.c_str());
2597 
2598  supervisor_node_get_type_name_srv.request.node = root_node;
2599  supervisor_node_get_type_name_client.call(supervisor_node_get_type_name_srv);
2600  ROS_INFO("Got type name of root node: %s.", supervisor_node_get_type_name_srv.response.name.c_str());
2601 
2602  supervisor_node_get_type_name_srv.request.node = self_node;
2603  supervisor_node_get_type_name_client.call(supervisor_node_get_type_name_srv);
2604  ROS_INFO("Got type name of self node: %s.", supervisor_node_get_type_name_srv.response.name.c_str());
2605 
2606  supervisor_get_from_def_srv.request.name = "GROUND";
2607  supervisor_get_from_def_client.call(supervisor_get_from_def_srv);
2608  uint64_t ground_node = 0;
2609  if (supervisor_get_from_def_srv.response.node != 0) {
2610  ROS_INFO("Got from DEF GROUND node: %ld.", supervisor_get_from_def_srv.response.node);
2611  ground_node = supervisor_get_from_def_srv.response.node;
2612  } else
2613  ROS_ERROR("Could not get node from DEF GROUND.");
2614 
2615  supervisor_node_get_type_name_srv.request.node = ground_node;
2616  supervisor_node_get_type_name_client.call(supervisor_node_get_type_name_srv);
2617  ROS_INFO("Got type name of GROUND node: %s.", supervisor_node_get_type_name_srv.response.name.c_str());
2618 
2619  time_step_client.call(time_step_srv);
2620 
2621  ros::ServiceClient supervisor_node_get_base_type_name_client;
2622  webots_ros::node_get_name supervisor_node_get_base_type_name_srv;
2623  supervisor_node_get_base_type_name_client =
2624  n.serviceClient<webots_ros::node_get_name>(model_name + "/supervisor/node/get_base_type_name");
2625  supervisor_node_get_base_type_name_srv.request.node = ground_node;
2626  supervisor_node_get_base_type_name_client.call(supervisor_node_get_base_type_name_srv);
2627  ROS_INFO("Got base type name of GROUND node: %s.", supervisor_node_get_base_type_name_srv.response.name.c_str());
2628 
2629  supervisor_node_get_base_type_name_client.shutdown();
2630  time_step_client.call(time_step_srv);
2631 
2632  ros::ServiceClient supervisor_node_get_def_client;
2633  webots_ros::node_get_name supervisor_node_get_def_srv;
2634  supervisor_node_get_def_client = n.serviceClient<webots_ros::node_get_name>(model_name + "/supervisor/node/get_def");
2635  supervisor_node_get_def_srv.request.node = ground_node;
2636  supervisor_node_get_def_client.call(supervisor_node_get_def_srv);
2637  ROS_INFO("Got DEF name of GROUND node: %s.", supervisor_node_get_def_srv.response.name.c_str());
2638 
2639  supervisor_node_get_def_client.shutdown();
2640  time_step_client.call(time_step_srv);
2641 
2642  ros::ServiceClient supervisor_node_get_position_client;
2643  webots_ros::node_get_position supervisor_node_get_position_srv;
2644  supervisor_node_get_position_client =
2645  n.serviceClient<webots_ros::node_get_position>(model_name + "/supervisor/node/get_position");
2646 
2647  supervisor_node_get_position_srv.request.node = from_def_node;
2648  supervisor_node_get_position_client.call(supervisor_node_get_position_srv);
2649  ROS_INFO("From_def node got position: x = %f y = %f z = %f.", supervisor_node_get_position_srv.response.position.x,
2650  supervisor_node_get_position_srv.response.position.y, supervisor_node_get_position_srv.response.position.z);
2651 
2652  supervisor_node_get_position_client.shutdown();
2653  time_step_client.call(time_step_srv);
2654 
2655  ros::ServiceClient supervisor_node_get_orientation_client;
2656  webots_ros::node_get_orientation supervisor_node_get_orientation_srv;
2657  supervisor_node_get_orientation_client =
2658  n.serviceClient<webots_ros::node_get_orientation>(model_name + "/supervisor/node/get_orientation");
2659 
2660  supervisor_node_get_orientation_srv.request.node = from_def_node;
2661  supervisor_node_get_orientation_client.call(supervisor_node_get_orientation_srv);
2662  ROS_INFO(
2663  "From_def orientation quaternion is:\nw=%f x=%f y=%f z=%f.", supervisor_node_get_orientation_srv.response.orientation.w,
2664  supervisor_node_get_orientation_srv.response.orientation.x, supervisor_node_get_orientation_srv.response.orientation.y,
2665  supervisor_node_get_orientation_srv.response.orientation.z);
2666 
2667  supervisor_node_get_orientation_client.shutdown();
2668  time_step_client.call(time_step_srv);
2669 
2670  ros::ServiceClient supervisor_node_get_center_of_mass_client;
2671  webots_ros::node_get_center_of_mass supervisor_node_get_center_of_mass_srv;
2672  supervisor_node_get_center_of_mass_client =
2673  n.serviceClient<webots_ros::node_get_center_of_mass>(model_name + "/supervisor/node/get_center_of_mass");
2674 
2675  supervisor_node_get_center_of_mass_srv.request.node = from_def_node;
2676  supervisor_node_get_center_of_mass_client.call(supervisor_node_get_center_of_mass_srv);
2677  ROS_INFO("From_def node's center of mass coordinates are: x = %f y = %f z = %f.",
2678  supervisor_node_get_center_of_mass_srv.response.centerOfMass.x,
2679  supervisor_node_get_center_of_mass_srv.response.centerOfMass.y,
2680  supervisor_node_get_center_of_mass_srv.response.centerOfMass.z);
2681 
2682  supervisor_node_get_center_of_mass_client.shutdown();
2683  time_step_client.call(time_step_srv);
2684 
2685  ros::ServiceClient supervisor_node_get_number_of_contact_points_client;
2686  webots_ros::node_get_number_of_contact_points supervisor_node_get_number_of_contact_points_srv;
2687  supervisor_node_get_number_of_contact_points_client = n.serviceClient<webots_ros::node_get_number_of_contact_points>(
2688  model_name + "/supervisor/node/get_number_of_contact_points");
2689 
2690  supervisor_node_get_number_of_contact_points_srv.request.node = from_def_node;
2691  supervisor_node_get_number_of_contact_points_client.call(supervisor_node_get_number_of_contact_points_srv);
2692  ROS_INFO("From_def node got %d contact points.",
2693  supervisor_node_get_number_of_contact_points_srv.response.numberOfContactPoints);
2694 
2695  supervisor_node_get_number_of_contact_points_client.shutdown();
2696  time_step_client.call(time_step_srv);
2697 
2698  ros::ServiceClient supervisor_node_get_contact_point_client;
2699  webots_ros::node_get_contact_point supervisor_node_get_contact_point_srv;
2700  supervisor_node_get_contact_point_client =
2701  n.serviceClient<webots_ros::node_get_contact_point>(model_name + "/supervisor/node/get_contact_point");
2702 
2703  supervisor_node_get_contact_point_srv.request.node = from_def_node;
2704  supervisor_node_get_contact_point_srv.request.index = 0;
2705  supervisor_node_get_contact_point_client.call(supervisor_node_get_contact_point_srv);
2706  ROS_INFO("From_def_node first contact point is at x = %f, y = %f z = %f.",
2707  supervisor_node_get_contact_point_srv.response.point.x, supervisor_node_get_contact_point_srv.response.point.y,
2708  supervisor_node_get_contact_point_srv.response.point.z);
2709 
2710  supervisor_node_get_contact_point_client.shutdown();
2711  time_step_client.call(time_step_srv);
2712 
2713  // test get_static_balance
2714  // if the node isn't a top Solid webots will throw a warning but still return true to ros
2715  ros::ServiceClient supervisor_node_get_static_balance_client;
2716  webots_ros::node_get_static_balance supervisor_node_get_static_balance_srv;
2717  supervisor_node_get_static_balance_client =
2718  n.serviceClient<webots_ros::node_get_static_balance>(model_name + "/supervisor/node/get_static_balance");
2719 
2720  supervisor_node_get_static_balance_srv.request.node = from_def_node;
2721  supervisor_node_get_static_balance_client.call(supervisor_node_get_static_balance_srv);
2722  ROS_INFO("From_def node balance is %d.", supervisor_node_get_static_balance_srv.response.balance);
2723 
2724  supervisor_node_get_static_balance_client.shutdown();
2725  time_step_client.call(time_step_srv);
2726 
2727  // test reset_physics
2728  // if the node isn't a top Solid webots will throw a warning but still return true to ros
2729  ros::ServiceClient supervisor_node_reset_physics_client =
2730  n.serviceClient<webots_ros::node_reset_functions>(model_name + "/supervisor/node/reset_physics");
2731  webots_ros::node_reset_functions supervisor_node_reset_physics_srv;
2732 
2733  supervisor_node_reset_physics_srv.request.node = from_def_node;
2734  if (supervisor_node_reset_physics_client.call(supervisor_node_reset_physics_srv) &&
2735  supervisor_node_reset_physics_srv.response.success == 1)
2736  ROS_INFO("Node physics has been reset successfully.");
2737  else
2738  ROS_ERROR("Failed to call service node_reset_physics.");
2739 
2740  supervisor_node_reset_physics_client.shutdown();
2741  time_step_client.call(time_step_srv);
2742 
2743  // test restart_controller
2744  ros::ServiceClient supervisor_node_restart_controller_client =
2745  n.serviceClient<webots_ros::node_reset_functions>(model_name + "/supervisor/node/restart_controller");
2746  webots_ros::node_reset_functions supervisor_node_restart_controller_srv;
2747 
2748  supervisor_node_restart_controller_srv.request.node = from_def_node;
2749  if (supervisor_node_restart_controller_client.call(supervisor_node_restart_controller_srv) &&
2750  supervisor_node_restart_controller_srv.response.success == 1)
2751  ROS_INFO("Robot controller has been restarted successfully.");
2752  else
2753  ROS_ERROR("Failed to call service node_restart_controller.");
2754 
2755  supervisor_node_restart_controller_client.shutdown();
2756  time_step_client.call(time_step_srv);
2757 
2758  ros::ServiceClient supervisor_node_get_field_client;
2759  webots_ros::node_get_field supervisor_node_get_field_srv;
2760  supervisor_node_get_field_client = n.serviceClient<webots_ros::node_get_field>(model_name + "/supervisor/node/get_field");
2761 
2762  supervisor_node_get_field_srv.request.node = root_node;
2763  supervisor_node_get_field_srv.request.fieldName = "children";
2764  supervisor_node_get_field_client.call(supervisor_node_get_field_srv);
2765  uint64_t field = supervisor_node_get_field_srv.response.field;
2766 
2767  supervisor_node_get_field_client.shutdown();
2768  time_step_client.call(time_step_srv);
2769 
2770  ros::ServiceClient supervisor_field_get_type_client;
2771  webots_ros::field_get_type supervisor_field_get_type_srv;
2772  supervisor_field_get_type_client = n.serviceClient<webots_ros::field_get_type>(model_name + "/supervisor/field/get_type");
2773 
2774  supervisor_field_get_type_srv.request.field = field;
2775  supervisor_field_get_type_client.call(supervisor_field_get_type_srv);
2776  ROS_INFO("World's children field is of type %d.", supervisor_field_get_type_srv.response.type);
2777 
2778  supervisor_field_get_type_client.shutdown();
2779  time_step_client.call(time_step_srv);
2780 
2781  ros::ServiceClient supervisor_field_get_type_name_client;
2782  webots_ros::field_get_type_name supervisor_field_get_type_name_srv;
2783  supervisor_field_get_type_name_client =
2784  n.serviceClient<webots_ros::field_get_type_name>(model_name + "/supervisor/field/get_type_name");
2785 
2786  supervisor_field_get_type_name_srv.request.field = field;
2787  supervisor_field_get_type_name_client.call(supervisor_field_get_type_name_srv);
2788  ROS_INFO("Also known as %s.", supervisor_field_get_type_name_srv.response.name.c_str());
2789 
2790  supervisor_field_get_type_name_client.shutdown();
2791  time_step_client.call(time_step_srv);
2792 
2793  ros::ServiceClient supervisor_field_get_count_client;
2794  webots_ros::field_get_count supervisor_field_get_count_srv;
2795  supervisor_field_get_count_client = n.serviceClient<webots_ros::field_get_count>(model_name + "/supervisor/field/get_count");
2796 
2797  supervisor_field_get_count_srv.request.field = field;
2798  supervisor_field_get_count_client.call(supervisor_field_get_count_srv);
2799  if (supervisor_field_get_count_srv.response.count != -1)
2800  ROS_INFO("There is %d nodes in this field.", supervisor_field_get_count_srv.response.count);
2801  else
2802  ROS_ERROR("Illegal call to Field::getCount() argument must be multiple fields.");
2803 
2804  supervisor_field_get_count_client.shutdown();
2805  time_step_client.call(time_step_srv);
2806 
2807  supervisor_node_get_field_srv.request.node = from_def_node;
2808  supervisor_node_get_field_srv.request.fieldName = "name";
2809  supervisor_node_get_field_client.call(supervisor_node_get_field_srv);
2810  field = supervisor_node_get_field_srv.response.field;
2811 
2812  ros::ServiceClient supervisor_field_set_string_client;
2813  webots_ros::field_set_string supervisor_field_set_string_srv;
2814  supervisor_field_set_string_client =
2815  n.serviceClient<webots_ros::field_set_string>(model_name + "/supervisor/field/set_string");
2816 
2817  supervisor_field_set_string_srv.request.field = field;
2818  supervisor_field_set_string_srv.request.value = "solid_test";
2819  if (supervisor_field_set_string_client.call(supervisor_field_set_string_srv) &&
2820  supervisor_field_set_string_srv.response.success == 1)
2821  ROS_INFO("Field's string updated to: 'solid_test'.");
2822  else
2823  ROS_ERROR("Failed to call service field_set_string.");
2824 
2825  supervisor_field_set_string_client.shutdown();
2826  time_step_client.call(time_step_srv);
2827 
2828  ros::ServiceClient supervisor_field_get_string_client;
2829  webots_ros::field_get_string supervisor_field_get_string_srv;
2830  supervisor_field_get_string_client =
2831  n.serviceClient<webots_ros::field_get_string>(model_name + "/supervisor/field/get_string");
2832 
2833  supervisor_field_get_string_srv.request.field = field;
2834  supervisor_field_get_string_client.call(supervisor_field_get_string_srv);
2835  ROS_INFO("Field contains \"%s\".", supervisor_field_get_string_srv.response.value.c_str());
2836 
2837  supervisor_field_get_string_client.shutdown();
2838  time_step_client.call(time_step_srv);
2839 
2840  supervisor_node_get_field_srv.request.node = root_node;
2841  supervisor_node_get_field_srv.request.fieldName = "children";
2842  supervisor_node_get_field_client.call(supervisor_node_get_field_srv);
2843  field = supervisor_node_get_field_srv.response.field;
2844 
2845  ros::ServiceClient supervisor_field_get_node_client;
2846  webots_ros::field_get_node supervisor_field_get_node_srv;
2847  supervisor_field_get_node_client = n.serviceClient<webots_ros::field_get_node>(model_name + "/supervisor/field/get_node");
2848 
2849  supervisor_field_get_node_srv.request.field = field;
2850  supervisor_field_get_node_srv.request.index = 7;
2851  supervisor_field_get_node_client.call(supervisor_field_get_node_srv);
2852 
2853  supervisor_node_get_type_name_srv.request.node = supervisor_field_get_node_srv.response.node;
2854  supervisor_node_get_type_name_client.call(supervisor_node_get_type_name_srv);
2855  ROS_INFO("Node got from field_get_node is of type %s.", supervisor_node_get_type_name_srv.response.name.c_str());
2856 
2857  // supervisor_node_get_from_id
2858  supervisor_get_from_def_srv.request.name = "CONE";
2859  supervisor_get_from_def_client.call(supervisor_get_from_def_srv);
2860  uint64_t cone_node = 0;
2861  if (supervisor_get_from_def_srv.response.node != 0) {
2862  ROS_INFO("Got CONE node from DEF: %lu.", supervisor_get_from_def_srv.response.node);
2863  cone_node = supervisor_get_from_def_srv.response.node;
2864  } else
2865  ROS_ERROR("could not get CONE node from DEF.");
2866 
2867  supervisor_node_get_type_name_client.shutdown();
2868  supervisor_get_from_def_client.shutdown();
2869  supervisor_field_get_node_client.shutdown();
2870  time_step_client.call(time_step_srv);
2871 
2872  ros::ServiceClient node_get_id_client;
2873  webots_ros::node_get_id node_get_id_srv;
2874  node_get_id_client = n.serviceClient<webots_ros::node_get_id>(model_name + "/supervisor/node/get_id");
2875  node_get_id_srv.request.node = cone_node;
2876  node_get_id_client.call(node_get_id_srv);
2877  int cone_node_id = node_get_id_srv.response.id;
2878  if (cone_node_id > 0)
2879  ROS_INFO("Node id got successfully.");
2880  else
2881  ROS_ERROR("Failed to call service node_get_id.");
2882 
2883  node_get_id_client.shutdown();
2884  time_step_client.call(time_step_srv);
2885 
2886  // supervisor_get_from_id
2887  webots_ros::supervisor_get_from_id supervisor_get_from_id_srv;
2888  node_get_id_client = n.serviceClient<webots_ros::supervisor_get_from_id>(model_name + "/supervisor/get_from_id");
2889  supervisor_get_from_id_srv.request.id = cone_node_id;
2890  node_get_id_client.call(supervisor_get_from_id_srv);
2891  uint64_t cone_node_copy = supervisor_get_from_id_srv.response.node;
2892  if (cone_node_copy == cone_node)
2893  ROS_INFO("Cone node got successfully from id.");
2894  else
2895  ROS_ERROR("Failed to call service supervisor_get_from_id.");
2896 
2897  node_get_id_client.shutdown();
2898  time_step_client.call(time_step_srv);
2899 
2900  // node_set_velocity
2901  ros::ServiceClient node_velocity_client;
2902  webots_ros::node_set_velocity node_set_velocity_srv;
2903  node_velocity_client = n.serviceClient<webots_ros::node_set_velocity>(model_name + "/supervisor/node/set_velocity");
2904  node_set_velocity_srv.request.node = cone_node;
2905  node_set_velocity_srv.request.velocity.linear.x = 0.0;
2906  node_set_velocity_srv.request.velocity.linear.y = 0.0;
2907  node_set_velocity_srv.request.velocity.linear.z = 1.0;
2908  node_set_velocity_srv.request.velocity.angular.x = 0.0;
2909  node_set_velocity_srv.request.velocity.angular.y = 0.0;
2910  node_set_velocity_srv.request.velocity.angular.z = 0.0;
2911  if (node_velocity_client.call(node_set_velocity_srv) && node_set_velocity_srv.response.success == 1)
2912  ROS_INFO("Node velocity set successfully.");
2913  else
2914  ROS_ERROR("Failed to call service node_set_velocity.");
2915 
2916  node_velocity_client.shutdown();
2917  time_step_client.call(time_step_srv);
2918 
2919  // node_get_velocity
2920  webots_ros::node_get_velocity node_get_velocity_srv;
2921  node_velocity_client = n.serviceClient<webots_ros::node_get_velocity>(model_name + "/supervisor/node/get_velocity");
2922  node_get_velocity_srv.request.node = cone_node;
2923  node_velocity_client.call(node_get_velocity_srv);
2924  if (node_get_velocity_srv.response.velocity.linear.z > 0.8)
2925  ROS_INFO("Node velocity get successfully.");
2926  else
2927  ROS_ERROR("Failed to call service node_get_velocity.");
2928 
2929  node_velocity_client.shutdown();
2930  time_step_client.call(time_step_srv);
2931 
2932  // node_get_parent
2933  ros::ServiceClient node_get_parent_node_client;
2934  webots_ros::node_get_parent_node node_get_parent_node_srv;
2935  node_get_parent_node_client =
2936  n.serviceClient<webots_ros::node_get_parent_node>(model_name + "/supervisor/node/get_parent_node");
2937  node_get_parent_node_srv.request.node = cone_node;
2938  node_get_parent_node_client.call(node_get_parent_node_srv);
2939  if (node_get_parent_node_srv.response.node == root_node)
2940  ROS_INFO("Node parent got successfully.");
2941  else
2942  ROS_ERROR("Failed to call service node_get_parent_node.");
2943 
2944  node_get_parent_node_client.shutdown();
2945  time_step_client.call(time_step_srv);
2946 
2947  // movie
2948  ros::ServiceClient supervisor_movie_is_ready_client;
2949  webots_ros::node_get_status supervisor_movie_is_ready_srv;
2950  supervisor_movie_is_ready_client = n.serviceClient<webots_ros::node_get_status>(model_name + "/supervisor/movie_is_ready");
2951 
2952  if (supervisor_movie_is_ready_client.call(supervisor_movie_is_ready_srv) &&
2953  supervisor_movie_is_ready_srv.response.status == 1)
2954  ROS_INFO("Ready to record a movie.");
2955  else
2956  ROS_ERROR("Failed to call service supervisor_movie_is_ready.");
2957 
2958  supervisor_movie_is_ready_client.shutdown();
2959  time_step_client.call(time_step_srv);
2960 
2961  ros::ServiceClient supervisor_movie_start_client;
2962  webots_ros::supervisor_movie_start_recording supervisor_movie_start_srv;
2963  supervisor_movie_start_client =
2964  n.serviceClient<webots_ros::supervisor_movie_start_recording>(model_name + "/supervisor/movie_start_recording");
2965 
2966  supervisor_movie_start_srv.request.filename = std::string(getenv("HOME")) + std::string("/movie_test.mp4");
2967  supervisor_movie_start_srv.request.width = 480;
2968  supervisor_movie_start_srv.request.height = 360;
2969  supervisor_movie_start_srv.request.codec = 1337;
2970  supervisor_movie_start_srv.request.quality = 100;
2971  supervisor_movie_start_srv.request.acceleration = 1;
2972  supervisor_movie_start_srv.request.caption = false;
2973  if (supervisor_movie_start_client.call(supervisor_movie_start_srv) && supervisor_movie_start_srv.response.success == 1)
2974  ROS_INFO("Movie started successfully.");
2975  else
2976  ROS_ERROR("Failed to call service movie_start_recording.");
2977 
2978  supervisor_movie_start_client.shutdown();
2979  for (int i = 0; i < 25; ++i)
2980  time_step_client.call(time_step_srv);
2981 
2982  ros::ServiceClient supervisor_movie_stop_client;
2983  webots_ros::get_bool supervisor_movie_stop_srv;
2984  supervisor_movie_stop_client = n.serviceClient<webots_ros::get_bool>(model_name + "/supervisor/movie_stop_recording");
2985 
2986  if (supervisor_movie_stop_client.call(supervisor_movie_stop_srv) && supervisor_movie_stop_srv.response.value)
2987  ROS_INFO("Movie stopped successfully.");
2988  else
2989  ROS_ERROR("Failed to call service movie_stop_recording.");
2990 
2991  supervisor_movie_stop_client.shutdown();
2992  time_step_client.call(time_step_srv);
2993 
2994  ros::ServiceClient supervisor_movie_failed_client;
2995  webots_ros::node_get_status supervisor_movie_failed_srv;
2996  supervisor_movie_failed_client = n.serviceClient<webots_ros::node_get_status>(model_name + "/supervisor/movie_failed");
2997 
2998  if (supervisor_movie_failed_client.call(supervisor_movie_failed_srv) && supervisor_movie_failed_srv.response.status == 0)
2999  ROS_INFO("Movie recording executing successfully.");
3000  else
3001  ROS_ERROR("Failed movie recording.");
3002 
3003  supervisor_movie_failed_client.shutdown();
3004  time_step_client.call(time_step_srv);
3005 
3006  supervisor_set_label_srv.request.label = "";
3007  supervisor_set_label_client.call(supervisor_set_label_srv);
3008 
3009  supervisor_set_label_client.shutdown();
3010  time_step_client.call(time_step_srv);
3011 
3012  // field_remove
3013  ros::ServiceClient remove_node_client;
3014  webots_ros::field_remove field_remove_srv;
3015  remove_node_client = n.serviceClient<webots_ros::field_remove>(model_name + "/supervisor/field/remove");
3016  field_remove_srv.request.field = field;
3017  field_remove_srv.request.index = 5;
3018  if (remove_node_client.call(field_remove_srv) && field_remove_srv.response.success == 1)
3019  ROS_INFO("Field node removed successfully.");
3020  else
3021  ROS_ERROR("Failed to call service field_remove.");
3022 
3023  remove_node_client.shutdown();
3024  time_step_client.call(time_step_srv);
3025 
3026  // node_remove
3027  webots_ros::node_remove node_remove_srv;
3028  remove_node_client = n.serviceClient<webots_ros::node_remove>(model_name + "/supervisor/node/remove");
3029  node_remove_srv.request.node = cone_node;
3030  remove_node_client.call(node_remove_srv);
3031  int success1 = node_remove_srv.response.success;
3032  if (success1 == 1)
3033  ROS_INFO("Node removed successfully.");
3034  else
3035  ROS_ERROR("Failed to call service node_removed.");
3036 
3037  remove_node_client.shutdown();
3038  time_step_client.call(time_step_srv);
3039 
3040  // html robot window
3041  ros::ServiceClient wwi_send_client;
3042  wwi_send_client = n.serviceClient<webots_ros::set_string>(model_name + "/robot/wwi_send_text");
3043  webots_ros::set_string wwi_send_srv;
3044  wwi_send_srv.request.value = "test wwi functions from complete_test controller.";
3045  if (wwi_send_client.call(wwi_send_srv) && wwi_send_srv.response.success == 1)
3046  ROS_INFO("Text to robot window successfully sent.");
3047  else
3048  ROS_ERROR("Failed to call service robot/wwi_send_text.");
3049 
3050  wwi_send_client.shutdown();
3051  time_step_client.call(time_step_srv);
3052 
3053  ros::ServiceClient wwi_receive_client;
3054  wwi_receive_client = n.serviceClient<webots_ros::get_string>(model_name + "/robot/wwi_receive_text");
3055  webots_ros::get_string wwi_receive_srv;
3056  if (wwi_receive_client.call(wwi_receive_srv) &&
3057  wwi_receive_srv.response.value.compare("Answer: test wwi functions from complete_test controller.") == 0)
3058  ROS_INFO("Text from robot window successfully received.");
3059  else
3060  ROS_ERROR("Failed to call service robot/wwi_receive_text.");
3061 
3062  wwi_receive_client.shutdown();
3063  time_step_client.call(time_step_srv);
3064 
3065  // virtual reality headset
3066  ros::ServiceClient virtual_reality_headset_client;
3067  webots_ros::get_bool supervisor_virtual_reality_headset_is_used_srv;
3068  virtual_reality_headset_client =
3069  n.serviceClient<webots_ros::get_bool>(model_name + "/supervisor/vitual_reality_headset_is_used");
3070  virtual_reality_headset_client.call(supervisor_virtual_reality_headset_is_used_srv);
3071  bool used = supervisor_virtual_reality_headset_is_used_srv.response.value;
3072  // to test this service we assume no virtual reality headset is connected
3073  if (!used)
3074  ROS_INFO("No virtual reality headset connected.");
3075  else
3076  ROS_ERROR("Virtual reality headset wrongly detected.");
3077 
3078  virtual_reality_headset_client.shutdown();
3079  time_step_client.call(time_step_srv);
3080 
3081  // test field_import_node
3082  // this test is disabled as it needs a webots object file but it will work if you export the cone_test solid from the world
3083  // before
3084  // ros::ServiceClient supervisor_field_import_node_client;
3085  // webots_ros::field_import_node supervisor_field_import_node_srv;
3086  // supervisor_field_import_node_client =
3087  // n.serviceClient<webots_ros::field_import_node>(model_name+"/supervisor/field/import_node");
3088  //
3089  // supervisor_field_import_node_srv.request.field = field;
3090  // supervisor_field_import_node_srv.request.position = 6;
3091  // supervisor_field_import_node_srv.request.filename = "cone_test.wbo";
3092  // if (supervisor_field_import_node_client.call(supervisor_field_import_node_srv) &&
3093  // supervisor_field_import_node_srv.response.success == 1)
3094  // ROS_INFO("New cone add in world.");
3095  // else
3096  // ROS_ERROR("Failed to call service field_import_node.");
3097 
3098  // The next 2 tests are commented but works if you want to use them.
3099  // Since they stop simulation we can't use them if we wants to do other tests afterwards
3100 
3101  //~ ros::ServiceClient supervisor_simulation_quit_client;
3102  //~ webots_ros::set_int supervisor_simulation_quit_srv;
3103  //~ supervisor_simulation_quit_client = n.serviceClient<webots_ros::set_int>(model_name+"/supervisor/simulation_quit");
3104  //~
3105  //~ supervisor_simulation_quit_srv.request.value = EXIT_SUCCESS;
3106  //~ if (supervisor_simulation_quit_client.call(supervisor_simulation_quit_srv) &&
3107  //~ supervisor_simulation_quit_srv.response.success)
3108  //~ ROS_INFO("Webots quit successfully.");
3109  //~ else
3110  //~ ROS_ERROR("Failed to call service simulation_quit.");
3111 
3112  //~ ros::ServiceClient supervisor_simulation_revert_client;
3113  //~ webots_ros::get_bool supervisor_simulation_revert_srv;
3114  //~ supervisor_simulation_revert_client = n.serviceClient<webots_ros::get_bool>(model_name+"/supervisor/simulation_revert");
3115  //~
3116  //~ if (supervisor_simulation_revert_client.call(supervisor_simulation_revert_srv) &&
3117  //~ supervisor_simulation_revert_srv.response.value)
3118  //~ ROS_INFO("Simulation has revert successfully.");
3119  //~ else
3120  //~ ROS_ERROR("Failed to call service simulation_revert.");
3121 
3122  // end of tests
3123  time_step_srv.request.value = 0;
3124  if (time_step_client.call(time_step_srv) && time_step_srv.response.success)
3125  ROS_INFO("Robot's time step called to end tests.");
3126  else
3127  ROS_ERROR("Failed to call service time_step to end tests.");
3128 
3129  time_step_client.shutdown();
3130 
3131  ros::shutdown();
3132 
3133  printf("\nTest Completed\n");
3134  return 0;
3135 }
double compassValues[3]
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void lightSensorCallback(const sensor_msgs::Illuminance::ConstPtr &value)
#define TIME_STEP
double inertialUnitValues[4]
void joystickCallback(const webots_ros::Int8Stamped::ConstPtr &value)
void gyroCallback(const sensor_msgs::Imu::ConstPtr &values)
void receiverCallback(const webots_ros::StringStamped::ConstPtr &value)
void battery_sensorCallback(const webots_ros::Float64Stamped::ConstPtr &value)
int main(int argc, char **argv)
void lidarCallback(const sensor_msgs::Image::ConstPtr &image)
double accelerometerValues[3]
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void distance_sensorCallback(const sensor_msgs::Range::ConstPtr &value)
webots_ros::set_int time_step_srv
void keyboardCallback(const webots_ros::Int32Stamped::ConstPtr &value)
int connectorPresence
double touchSensorValues[3]
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
void connectorCallback(const webots_ros::Int8Stamped::ConstPtr &value)
void GPSCallback(const sensor_msgs::NavSatFix::ConstPtr &values)
void modelNameCallback(const std_msgs::String::ConstPtr &name)
ros::ServiceClient time_step_client
void accelerometerCallback(const sensor_msgs::Imu::ConstPtr &values)
ros::NodeHandle * n
Definition: pioneer3at.cpp:40
void touchSensorBumperCallback(const webots_ros::BoolStamped::ConstPtr &value)
void rangeFinderCallback(const sensor_msgs::Image::ConstPtr &image)
void quit(int sig)
static int model_count
#define ROS_INFO(...)
void touchSensorCallback(const webots_ros::Float64Stamped::ConstPtr &value)
void radarTargetsNumberCallback(const webots_ros::Int8Stamped::ConstPtr &value)
uint32_t getNumPublishers() const
static vector< string > model_list
void positionSensorCallback(const webots_ros::Float64Stamped::ConstPtr &value)
void inertialUnitCallback(const sensor_msgs::Imu::ConstPtr &values)
double GPSValues[3]
void motorSensorCallback(const std_msgs::Float64::ConstPtr &value)
double GyroValues[3]
void cameraCallback(const sensor_msgs::Image::ConstPtr &values)
vector< unsigned char > imageColor
ROSCPP_DECL void shutdown()
void GPSSpeedCallback(const webots_ros::Float64Stamped::ConstPtr &value)
std::vector< unsigned char > image
Definition: e_puck_line.cpp:87
void touchSensor3DCallback(const geometry_msgs::WrenchStamped::ConstPtr &values)
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
vector< float > imageRangeFinder
void compassCallback(const sensor_msgs::MagneticField::ConstPtr &values)
void radarTargetsCallback(const webots_ros::RadarTarget::ConstPtr &target)


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