complete_test.cpp
Go to the documentation of this file.
1 // Copyright 1996-2020 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/PointStamped.h>
16 #include <geometry_msgs/Twist.h>
17 #include <geometry_msgs/WrenchStamped.h>
18 #include <sensor_msgs/Illuminance.h>
19 #include <sensor_msgs/Image.h>
20 #include <sensor_msgs/Imu.h>
21 #include <sensor_msgs/MagneticField.h>
22 #include <sensor_msgs/NavSatFix.h>
23 #include <sensor_msgs/Range.h>
24 #include <signal.h>
25 #include <std_msgs/Float32MultiArray.h>
26 #include <std_msgs/Float64.h>
27 #include <std_msgs/Float64MultiArray.h>
28 #include <std_msgs/String.h>
29 #include <std_msgs/UInt16.h>
30 #include <std_msgs/UInt8MultiArray.h>
31 #include <webots_ros/BoolStamped.h>
32 #include <webots_ros/Float64Stamped.h>
33 #include <webots_ros/Int32Stamped.h>
34 #include <webots_ros/Int8Stamped.h>
35 #include <webots_ros/RadarTarget.h>
36 #include <webots_ros/RecognitionObject.h>
37 #include <webots_ros/RecognitionObjects.h>
38 #include <webots_ros/StringStamped.h>
39 #include <cstdlib>
40 #include "ros/ros.h"
41 
42 #include <webots_ros/get_bool.h>
43 #include <webots_ros/get_float.h>
44 #include <webots_ros/get_float_array.h>
45 #include <webots_ros/get_int.h>
46 #include <webots_ros/get_string.h>
47 #include <webots_ros/get_uint64.h>
48 #include <webots_ros/get_urdf.h>
49 #include <webots_ros/set_bool.h>
50 #include <webots_ros/set_float.h>
51 #include <webots_ros/set_float_array.h>
52 #include <webots_ros/set_int.h>
53 #include <webots_ros/set_string.h>
54 
55 #include <webots_ros/camera_get_focus_info.h>
56 #include <webots_ros/camera_get_info.h>
57 #include <webots_ros/camera_get_zoom_info.h>
58 #include <webots_ros/display_draw_line.h>
59 #include <webots_ros/display_draw_oval.h>
60 #include <webots_ros/display_draw_pixel.h>
61 #include <webots_ros/display_draw_polygon.h>
62 #include <webots_ros/display_draw_rectangle.h>
63 #include <webots_ros/display_draw_text.h>
64 #include <webots_ros/display_get_info.h>
65 #include <webots_ros/display_image_copy.h>
66 #include <webots_ros/display_image_delete.h>
67 #include <webots_ros/display_image_load.h>
68 #include <webots_ros/display_image_new.h>
69 #include <webots_ros/display_image_paste.h>
70 #include <webots_ros/display_image_save.h>
71 #include <webots_ros/display_set_font.h>
72 #include <webots_ros/field_disable_sf_tracking.h>
73 #include <webots_ros/field_enable_sf_tracking.h>
74 #include <webots_ros/field_get_bool.h>
75 #include <webots_ros/field_get_color.h>
76 #include <webots_ros/field_get_count.h>
77 #include <webots_ros/field_get_float.h>
78 #include <webots_ros/field_get_int32.h>
79 #include <webots_ros/field_get_name.h>
80 #include <webots_ros/field_get_node.h>
81 #include <webots_ros/field_get_rotation.h>
82 #include <webots_ros/field_get_string.h>
83 #include <webots_ros/field_get_type.h>
84 #include <webots_ros/field_get_vec2f.h>
85 #include <webots_ros/field_get_vec3f.h>
86 #include <webots_ros/field_import_node.h>
87 #include <webots_ros/field_remove.h>
88 #include <webots_ros/field_set_bool.h>
89 #include <webots_ros/field_set_color.h>
90 #include <webots_ros/field_set_float.h>
91 #include <webots_ros/field_set_int32.h>
92 #include <webots_ros/field_set_rotation.h>
93 #include <webots_ros/field_set_string.h>
94 #include <webots_ros/field_set_vec2f.h>
95 #include <webots_ros/field_set_vec3f.h>
96 #include <webots_ros/lidar_get_frequency_info.h>
97 #include <webots_ros/lidar_get_info.h>
98 #include <webots_ros/motor_set_control_pid.h>
99 #include <webots_ros/node_add_force_or_torque.h>
100 #include <webots_ros/node_add_force_with_offset.h>
101 #include <webots_ros/node_disable_contact_points_tracking.h>
102 #include <webots_ros/node_disable_pose_tracking.h>
103 #include <webots_ros/node_enable_contact_points_tracking.h>
104 #include <webots_ros/node_enable_pose_tracking.h>
105 #include <webots_ros/node_get_center_of_mass.h>
106 #include <webots_ros/node_get_contact_point.h>
107 #include <webots_ros/node_get_contact_point_node.h>
108 #include <webots_ros/node_get_contact_points.h>
109 #include <webots_ros/node_get_field.h>
110 #include <webots_ros/node_get_field_by_index.h>
111 #include <webots_ros/node_get_id.h>
112 #include <webots_ros/node_get_name.h>
113 #include <webots_ros/node_get_number_of_contact_points.h>
114 #include <webots_ros/node_get_number_of_fields.h>
115 #include <webots_ros/node_get_orientation.h>
116 #include <webots_ros/node_get_parent_node.h>
117 #include <webots_ros/node_get_pose.h>
118 #include <webots_ros/node_get_position.h>
119 #include <webots_ros/node_get_static_balance.h>
120 #include <webots_ros/node_get_status.h>
121 #include <webots_ros/node_get_string.h>
122 #include <webots_ros/node_get_type.h>
123 #include <webots_ros/node_get_velocity.h>
124 #include <webots_ros/node_remove.h>
125 #include <webots_ros/node_reset_functions.h>
126 #include <webots_ros/node_set_joint_position.h>
127 #include <webots_ros/node_set_string.h>
128 #include <webots_ros/node_set_velocity.h>
129 #include <webots_ros/node_set_visibility.h>
130 #include <webots_ros/pen_set_ink_color.h>
131 #include <webots_ros/range_finder_get_info.h>
132 #include <webots_ros/receiver_get_emitter_direction.h>
133 #include <webots_ros/robot_get_device_list.h>
134 #include <webots_ros/robot_set_mode.h>
135 #include <webots_ros/robot_wait_for_user_input_event.h>
136 #include <webots_ros/save_image.h>
137 #include <webots_ros/speaker_play_sound.h>
138 #include <webots_ros/speaker_speak.h>
139 #include <webots_ros/supervisor_get_from_def.h>
140 #include <webots_ros/supervisor_get_from_id.h>
141 #include <webots_ros/supervisor_get_from_string.h>
142 #include <webots_ros/supervisor_movie_start_recording.h>
143 #include <webots_ros/supervisor_set_label.h>
144 #include <webots_ros/supervisor_virtual_reality_headset_get_orientation.h>
145 #include <webots_ros/supervisor_virtual_reality_headset_get_position.h>
146 
147 #define TIME_STEP 32
148 
149 using namespace std;
150 
151 static int model_count;
152 static vector<string> model_list;
153 static vector<unsigned char> imageColor;
154 static vector<float> imageRangeFinder;
155 static int connectorPresence = 0;
156 static double accelerometerValues[3] = {0, 0, 0};
157 static double compassValues[3] = {0, 0, 0};
158 static double GPSValues[3] = {0, 0, 0};
159 static double GyroValues[3] = {0, 0, 0};
160 static double inertialUnitValues[4] = {0, 0, 0, 0};
161 static double touchSensorValues[3] = {0, 0, 0};
162 static bool callbackCalled = false;
163 
165 webots_ros::set_int time_step_srv;
166 
167 void modelNameCallback(const std_msgs::String::ConstPtr &name) {
168  model_count++;
169  model_list.push_back(name->data);
170  ROS_INFO("Model #%d: %s.", model_count, model_list.back().c_str());
171  callbackCalled = true;
172 }
173 
174 void cameraCallback(const sensor_msgs::Image::ConstPtr &values) {
175  int i = 0;
176  imageColor.resize(values->step * values->height);
177  for (std::vector<unsigned char>::const_iterator it = values->data.begin(); it != values->data.end(); ++it) {
178  imageColor[i] = *it;
179  i++;
180  }
181  callbackCalled = true;
182 }
183 
184 void cameraRecognitionCallback(const webots_ros::RecognitionObjects::ConstPtr &objects) {
185  const int objectsCount = objects->objects.size();
186  ROS_INFO("Camera recognition saw %d objects (time: %d:%d).", objectsCount, objects->header.stamp.sec,
187  objects->header.stamp.nsec);
188  for (int i = 0; i < objectsCount; i++)
189  ROS_INFO(" Recognition object %d: '%s'.", i, objects->objects[i].model.c_str());
190  callbackCalled = true;
191 }
192 
193 void segmentationCallback(const sensor_msgs::Image::ConstPtr &values) {
194  ROS_INFO("Segmentation callback called.");
195  int i = 0;
196  imageColor.resize(values->step * values->height);
197  for (std::vector<unsigned char>::const_iterator it = values->data.begin(); it != values->data.end(); ++it) {
198  imageColor[i] = *it;
199  i++;
200  }
201  callbackCalled = true;
202 }
203 
204 void joystickCallback(const webots_ros::Int8Stamped::ConstPtr &value) {
205  ROS_INFO("Joystick button pressed: %d (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
206  callbackCalled = true;
207 }
208 
209 void keyboardCallback(const webots_ros::Int32Stamped::ConstPtr &value) {
210  ROS_INFO("Keyboard key pressed: %d (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
211  callbackCalled = true;
212 }
213 
214 void radarTargetsCallback(const webots_ros::RadarTarget::ConstPtr &target) {
215  ROS_INFO("Received a radar target with distance=%lf received power=%lf speed=%lf azimuth=%lf (time: %d:%d).",
216  target->distance, target->receivedPower, target->speed, target->azimuth, target->header.stamp.sec,
217  target->header.stamp.nsec);
218  callbackCalled = true;
219 }
220 
221 void radarTargetsNumberCallback(const webots_ros::Int8Stamped::ConstPtr &value) {
222  ROS_INFO("Number of target seen by the radar: %d (time: %d:%d).", value->data, value->header.stamp.sec,
223  value->header.stamp.nsec);
224  callbackCalled = true;
225 }
226 
227 void rangeFinderCallback(const sensor_msgs::Image::ConstPtr &image) {
228  int size = image->width * image->height;
229  imageRangeFinder.resize(size);
230 
231  const float *depth_data = reinterpret_cast<const float *>(&image->data[0]);
232  for (int i = 0; i < size; ++i)
233  imageRangeFinder[i] = depth_data[i];
234  callbackCalled = true;
235 }
236 
237 void lidarCallback(const sensor_msgs::Image::ConstPtr &image) {
238  callbackCalled = true;
239 }
240 
241 void connectorCallback(const webots_ros::Int8Stamped::ConstPtr &value) {
242  connectorPresence = value->data;
243 
244  ROS_INFO("Connector presence: %d (time: %d:%d).", connectorPresence, value->header.stamp.sec, value->header.stamp.nsec);
245  callbackCalled = true;
246 }
247 
248 void accelerometerCallback(const sensor_msgs::Imu::ConstPtr &values) {
249  accelerometerValues[0] = values->linear_acceleration.x;
250  accelerometerValues[1] = values->linear_acceleration.y;
251  accelerometerValues[2] = values->linear_acceleration.z;
252 
253  ROS_INFO("Accelerometer values are x=%f y=%f z=%f (time: %d:%d).", accelerometerValues[0], accelerometerValues[1],
254  accelerometerValues[2], values->header.stamp.sec, values->header.stamp.nsec);
255  callbackCalled = true;
256 }
257 
258 void altimeterCallback(const webots_ros::Float64Stamped::ConstPtr &value) {
259  ROS_INFO("Altimeter value is z=%f (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
260  callbackCalled = true;
261 }
262 
263 void battery_sensorCallback(const webots_ros::Float64Stamped::ConstPtr &value) {
264  ROS_INFO("Battery level is %f (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
265  callbackCalled = true;
266 }
267 
268 void compassCallback(const sensor_msgs::MagneticField::ConstPtr &values) {
269  compassValues[0] = values->magnetic_field.x;
270  compassValues[1] = values->magnetic_field.y;
271  compassValues[2] = values->magnetic_field.z;
272 
273  ROS_INFO("Compass values are x=%f y=%f z=%f (time: %d:%d).", compassValues[0], compassValues[1], compassValues[2],
274  values->header.stamp.sec, values->header.stamp.nsec);
275  callbackCalled = true;
276 }
277 
278 void distance_sensorCallback(const sensor_msgs::Range::ConstPtr &value) {
279  ROS_INFO("Distance from object is %f (time: %d:%d).", value->range, value->header.stamp.sec, value->header.stamp.nsec);
280  callbackCalled = true;
281 }
282 
283 void GPSCallback(const geometry_msgs::PointStamped::ConstPtr &values) {
284  GPSValues[0] = values->point.x;
285  GPSValues[1] = values->point.y;
286  GPSValues[2] = values->point.z;
287 
288  ROS_INFO("GPS values are x=%f y=%f z=%f (time: %d:%d).", GPSValues[0], GPSValues[1], GPSValues[2], values->header.stamp.sec,
289  values->header.stamp.nsec);
290  callbackCalled = true;
291 }
292 
293 void GPSSpeedCallback(const webots_ros::Float64Stamped::ConstPtr &value) {
294  ROS_INFO("GPS speed is: %fkm/h (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
295  callbackCalled = true;
296 }
297 
298 void gyroCallback(const sensor_msgs::Imu::ConstPtr &values) {
299  GyroValues[0] = values->angular_velocity.x;
300  GyroValues[1] = values->angular_velocity.y;
301  GyroValues[2] = values->angular_velocity.z;
302 
303  ROS_INFO("Gyro values are x=%f y=%f z=%f (time: %d:%d).", GyroValues[0], GyroValues[1], GyroValues[2],
304  values->header.stamp.sec, values->header.stamp.nsec);
305  callbackCalled = true;
306 }
307 
308 void inertialUnitCallback(const sensor_msgs::Imu::ConstPtr &values) {
309  inertialUnitValues[0] = values->orientation.x;
310  inertialUnitValues[1] = values->orientation.y;
311  inertialUnitValues[2] = values->orientation.z;
312  inertialUnitValues[3] = values->orientation.w;
313 
314  ROS_INFO("Inertial unit values (quaternions) are x=%f y=%f z=%f w=%f (time: %d:%d).", inertialUnitValues[0],
315  inertialUnitValues[1], inertialUnitValues[2], inertialUnitValues[2], values->header.stamp.sec,
316  values->header.stamp.nsec);
317  callbackCalled = true;
318 }
319 
320 void lightSensorCallback(const sensor_msgs::Illuminance::ConstPtr &value) {
321  ROS_INFO("Light intensity is %f.", value->illuminance);
322  callbackCalled = true;
323 }
324 
325 void motorSensorCallback(const webots_ros::Float64Stamped::ConstPtr &value) {
326  ROS_INFO("Motor sensor sent value %f.", value->data);
327  callbackCalled = true;
328 }
329 
330 void positionSensorCallback(const webots_ros::Float64Stamped::ConstPtr &value) {
331  ROS_INFO("Position sensor sent value %f (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
332  callbackCalled = true;
333 }
334 
335 void touchSensorCallback(const webots_ros::Float64Stamped::ConstPtr &value) {
336  ROS_INFO("Touch sensor sent value %f (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
337  callbackCalled = true;
338 }
339 
340 void touchSensorBumperCallback(const webots_ros::BoolStamped::ConstPtr &value) {
341  ROS_INFO("Touch sensor sent value %d (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
342  callbackCalled = true;
343 }
344 
345 void touchSensor3DCallback(const geometry_msgs::WrenchStamped::ConstPtr &values) {
346  touchSensorValues[0] = values->wrench.force.x;
347  touchSensorValues[1] = values->wrench.force.y;
348  touchSensorValues[2] = values->wrench.force.z;
349 
350  ROS_INFO("Touch sensor values are x = %f, y = %f and z = %f (time: %d:%d).", touchSensorValues[0], touchSensorValues[1],
351  touchSensorValues[2], values->header.stamp.sec, values->header.stamp.nsec);
352  callbackCalled = true;
353 }
354 
355 void receiverCallback(const webots_ros::StringStamped::ConstPtr &value) {
356  char *message = const_cast<char *>(value->data.c_str());
357  ROS_INFO("Received a message %s.", message);
358  callbackCalled = true;
359 }
360 
361 void quit(int sig) {
362  time_step_srv.request.value = 0;
364  ROS_INFO("User stopped the 'complete_test' node.");
365  ros::shutdown();
366  exit(0);
367 }
368 
369 int main(int argc, char **argv) {
370  string model_name = "my_robot";
371 
372  ros::init(argc, argv, "complete_test", ros::init_options::AnonymousName);
373  ros::NodeHandle n;
374 
375  signal(SIGINT, quit);
376 
377  ros::Subscriber name_sub = n.subscribe("model_name", 100, modelNameCallback);
378  while (model_count == 0 || model_count < name_sub.getNumPublishers()) {
379  ros::spinOnce();
380  ros::spinOnce();
381  ros::spinOnce();
382  }
383  ros::spinOnce();
384  name_sub.shutdown();
385 
387  // ROBOT METHODS TEST //
389 
390  int mode = 0;
391  string model;
392  string path;
393  string data;
394  vector<string> device_list;
395 
396  time_step_client = n.serviceClient<webots_ros::set_int>(model_name + "/robot/time_step");
397  time_step_srv.request.value = TIME_STEP;
398 
399  if (time_step_client.call(time_step_srv) && time_step_srv.response.success)
400  ROS_INFO("time_step service works.");
401  else
402  ROS_ERROR("Failed to call service time_step to update robot's time step.");
403 
404  ros::ServiceClient get_number_of_devices_client =
405  n.serviceClient<webots_ros::get_int>(model_name + "/robot/get_number_of_devices");
406  webots_ros::get_int get_number_of_devices_srv;
407 
408  if (get_number_of_devices_client.call(get_number_of_devices_srv)) {
409  int number_of_devices = get_number_of_devices_srv.response.value;
410  ROS_INFO("%s has %d devices.", model_name.c_str(), number_of_devices);
411  } else
412  ROS_ERROR("Failed to call service get_number_of_devices.");
413 
414  get_number_of_devices_client.shutdown();
416 
417  ros::ServiceClient device_list_client =
418  n.serviceClient<webots_ros::robot_get_device_list>(model_name + "/robot/get_device_list");
419  webots_ros::robot_get_device_list device_list_srv;
420 
421  if (device_list_client.call(device_list_srv)) {
422  device_list = device_list_srv.response.list;
423  for (unsigned int i = 0; i < device_list.size(); i++)
424  ROS_INFO("Device [%d]: %s.", i, device_list[i].c_str());
425  } else
426  ROS_ERROR("Failed to call service device_list.");
427 
428  device_list_client.shutdown();
430 
431  ros::ServiceClient urdf_client = n.serviceClient<webots_ros::get_urdf>(model_name + "/robot/get_urdf");
432  webots_ros::get_urdf urdf_srv;
433  urdf_srv.request.prefix = "unique_robot_prefix_name_";
434 
435  if (urdf_client.call(urdf_srv)) {
436  std::string urdf = urdf_srv.response.value;
437  if (urdf.find(urdf_srv.request.prefix) == std::string::npos)
438  ROS_ERROR("Invalid response from get_urdf.");
439  else
440  ROS_INFO("URDF has been successfully obtained.");
441  } else
442  ROS_ERROR("Failed to call service get_urdf.");
443 
444  urdf_client.shutdown();
446 
447  ros::ServiceClient get_basic_time_step_client =
448  n.serviceClient<webots_ros::get_float>(model_name + "/robot/get_basic_time_step");
449  webots_ros::get_float get_basic_time_step_srv;
450 
451  if (get_basic_time_step_client.call(get_basic_time_step_srv)) {
452  double basic_time_step = get_basic_time_step_srv.response.value;
453  ROS_INFO("%s has a basic time step of %f.", model_name.c_str(), basic_time_step);
454  } else
455  ROS_ERROR("Failed to call service get_basic_time_step.");
456 
457  get_basic_time_step_client.shutdown();
459 
460  ros::ServiceClient robot_get_custom_data_client =
461  n.serviceClient<webots_ros::get_string>(model_name + "/robot/get_custom_data");
462  webots_ros::get_string robot_get_custom_data_srv;
463 
464  if (robot_get_custom_data_client.call(robot_get_custom_data_srv)) {
465  data = robot_get_custom_data_srv.response.value;
466  ROS_INFO("Data of %s is %s.", model_name.c_str(), data.c_str());
467  } else
468  ROS_ERROR("Failed to call service robot_get_custom_data.");
469 
470  robot_get_custom_data_client.shutdown();
472 
473  ros::ServiceClient get_mode_client = n.serviceClient<webots_ros::get_int>(model_name + "/robot/get_mode");
474  webots_ros::get_int get_mode_srv;
475 
476  if (get_mode_client.call(get_mode_srv)) {
477  mode = get_mode_srv.response.value;
478  ROS_INFO("Mode of %s is %d.", model_name.c_str(), mode);
479  } else
480  ROS_ERROR("Failed to call service get_mode.");
481 
482  get_mode_client.shutdown();
484 
485  ros::ServiceClient get_model_client = n.serviceClient<webots_ros::get_string>(model_name + "/robot/get_model");
486  webots_ros::get_string get_model_srv;
487 
488  if (get_model_client.call(get_model_srv)) {
489  model = get_model_srv.response.value;
490  ROS_INFO("Model of %s is %s.", model_name.c_str(), model.c_str());
491  } else
492  ROS_ERROR("Failed to call service get_model.");
493 
494  get_model_client.shutdown();
496 
497  ros::ServiceClient get_project_path_client = n.serviceClient<webots_ros::get_string>(model_name + "/robot/get_project_path");
498  webots_ros::get_string get_project_path_srv;
499 
500  if (get_project_path_client.call(get_project_path_srv)) {
501  path = get_project_path_srv.response.value;
502  ROS_INFO("World path of %s is %s.", model_name.c_str(), path.c_str());
503  } else
504  ROS_ERROR("Failed to call service get_project_path.");
505 
506  get_project_path_client.shutdown();
508 
509  // robot_get_world_path
510  ros::ServiceClient get_world_path_client = n.serviceClient<webots_ros::get_string>(model_name + "/robot/get_world_path");
511  webots_ros::get_string get_world_path_srv;
512 
513  if (get_world_path_client.call(get_world_path_srv)) {
514  path = get_world_path_srv.response.value;
515  ROS_INFO("Project path of %s is %s.", model_name.c_str(), path.c_str());
516  } else
517  ROS_ERROR("Failed to call service get_project_path.");
518 
519  get_world_path_client.shutdown();
521 
522  ros::ServiceClient get_supervisor_client = n.serviceClient<webots_ros::get_bool>(model_name + "/robot/get_supervisor");
523  webots_ros::get_bool get_supervisor_srv;
524 
525  if (get_supervisor_client.call(get_supervisor_srv)) {
526  if (get_supervisor_srv.response.value)
527  ROS_INFO("%s is a supervisor.", model_name.c_str());
528  else
529  ROS_ERROR("%s isn't a supervisor.", model_name.c_str());
530  } else
531  ROS_ERROR("Failed to call service get_synchronization.");
532 
533  get_supervisor_client.shutdown();
535 
536  ros::ServiceClient get_synchronization_client =
537  n.serviceClient<webots_ros::get_bool>(model_name + "/robot/get_synchronization");
538  webots_ros::get_bool get_synchronization_srv;
539 
540  if (get_synchronization_client.call(get_synchronization_srv)) {
541  bool synchronization = get_synchronization_srv.response.value;
542  if (synchronization)
543  ROS_INFO("%s is sync.", model_name.c_str());
544  else
545  ROS_INFO("%s isn't sync.", model_name.c_str());
546  } else
547  ROS_ERROR("Failed to call service get_synchronization.");
548 
549  get_synchronization_client.shutdown();
551 
552  ros::ServiceClient get_time_client = n.serviceClient<webots_ros::get_float>(model_name + "/robot/get_time");
553  webots_ros::get_float get_time_srv;
554 
555  if (get_time_client.call(get_time_srv)) {
556  double time = get_time_srv.response.value;
557  ROS_INFO("Time for %s is %f.", model_name.c_str(), time);
558  } else
559  ROS_ERROR("Failed to call service get_time.");
560 
561  get_time_client.shutdown();
563 
564  ros::ServiceClient get_type_client = n.serviceClient<webots_ros::get_int>(model_name + "/robot/get_type");
565  webots_ros::get_int get_type_srv;
566 
567  if (get_type_client.call(get_type_srv)) {
568  int type = get_type_srv.response.value;
569  ROS_INFO("Type of %s is %d.", model_name.c_str(), type);
570  } else
571  ROS_ERROR("Failed to call service get_type.");
572 
573  get_type_client.shutdown();
575 
576  ros::ServiceClient robot_set_custom_data_client =
577  n.serviceClient<webots_ros::set_string>(model_name + "/robot/set_custom_data");
578  webots_ros::set_string robot_set_custom_data_srv;
579 
580  robot_set_custom_data_srv.request.value = "OVERWRITTEN";
581  if (robot_set_custom_data_client.call(robot_set_custom_data_srv)) {
582  if (robot_set_custom_data_srv.response.success)
583  ROS_INFO("Data of %s has been set to %s.", model_name.c_str(), data.c_str());
584  } else
585  ROS_ERROR("Failed to call service robot_set_custom_data.");
586 
587  robot_set_custom_data_client.shutdown();
589 
590  ros::ServiceClient set_mode_client = n.serviceClient<webots_ros::robot_set_mode>(model_name + "/robot/set_mode");
591  webots_ros::robot_set_mode set_mode_srv;
592 
593  set_mode_srv.request.mode = mode;
594  if (set_mode_client.call(set_mode_srv)) {
595  if (set_mode_srv.response.success == 1)
596  ROS_INFO("Mode of %s has been set to %d.", model_name.c_str(), mode);
597  } else
598  ROS_ERROR("Failed to call service set_mode.");
599 
600  set_mode_client.shutdown();
602 
603  ros::ServiceClient enable_keyboard_client = n.serviceClient<webots_ros::set_int>(model_name + "/keyboard/enable");
604  webots_ros::set_int enable_keyboard_srv;
605  ros::Subscriber sub_keyboard;
606 
607  enable_keyboard_srv.request.value = 32;
608  if (enable_keyboard_client.call(enable_keyboard_srv) && enable_keyboard_srv.response.success) {
609  ROS_INFO("Keyboard of %s has been enabled.", model_name.c_str());
610  sub_keyboard = n.subscribe(model_name + "/keyboard/key", 1, keyboardCallback);
611  ROS_INFO("Topics for keyboard initialized.");
612  callbackCalled = false;
613  while (sub_keyboard.getNumPublishers() == 0 && !callbackCalled) {
614  ros::spinOnce();
616  }
617  ROS_INFO("Topics for keyboard connected.");
618  } else
619  ROS_ERROR("Failed to enable keyboard.");
620 
621  ros::ServiceClient wait_for_user_input_event_client =
622  n.serviceClient<webots_ros::robot_wait_for_user_input_event>(model_name + "/robot/wait_for_user_input_event");
623  webots_ros::robot_wait_for_user_input_event wait_for_user_input_event_srv;
624 
625  wait_for_user_input_event_srv.request.eventType = 4; // WB_EVENT_KEYBOARD
626  wait_for_user_input_event_srv.request.timeout = 20;
627  if (wait_for_user_input_event_client.call(wait_for_user_input_event_srv))
628  ROS_INFO("Detected user input event: %d.", wait_for_user_input_event_srv.response.event);
629  else
630  ROS_ERROR("Failed to call service wait_for_user_input_event.");
631 
632  wait_for_user_input_event_client.shutdown();
634 
635  sub_keyboard.shutdown();
636  enable_keyboard_client.shutdown();
638 
640  // BREAK METHODS TEST //
642 
643  // brake_set_damping_constant
644  ros::ServiceClient brake_set_client = n.serviceClient<webots_ros::set_float>(model_name + "/my_brake/set_damping_constant");
645  webots_ros::set_float brake_set_srv;
646  brake_set_srv.request.value = 0.55;
647  if (brake_set_client.call(brake_set_srv) && brake_set_srv.response.success)
648  ROS_INFO("Brake damping constant set to 0.55.");
649  else
650  ROS_ERROR("Failed to call service brake_set_damping_constant.");
651 
652  brake_set_client.shutdown();
654 
655  // brake_get_motor_name
656  ros::ServiceClient brake_get_motor_name_client =
657  n.serviceClient<webots_ros::get_string>(model_name + "/my_brake/get_motor_name");
658  webots_ros::get_string brake_get_motor_name_srv;
659  if (brake_get_motor_name_client.call(brake_get_motor_name_srv)) {
660  ROS_INFO("Linear motor name returned from Brake API %s.", brake_get_motor_name_srv.response.value.c_str());
661  if (brake_get_motor_name_srv.response.value.compare("linear_motor") != 0)
662  ROS_ERROR("Failed to call service brake_get_motor_name: received '%s' instead of 'linear_motor'",
663  brake_get_motor_name_srv.response.value.c_str());
664  } else
665  ROS_ERROR("Failed to call service brake_get_motor_name.");
666 
667  brake_get_motor_name_client.shutdown();
669 
671  // CAMERA METHODS TEST //
673 
674  // camera_set_focal_distance
675  double focal_distance = 0.33;
676  ros::ServiceClient camera_set_client = n.serviceClient<webots_ros::set_float>(model_name + "/camera/set_focal_distance");
677  webots_ros::set_float camera_set_focal_distance_srv;
678  camera_set_focal_distance_srv.request.value = focal_distance;
679  if (camera_set_client.call(camera_set_focal_distance_srv) && camera_set_focal_distance_srv.response.success)
680  ROS_INFO("Camera focal distance set to %f.", focal_distance);
681  else
682  ROS_ERROR("Failed to call service camera_set_focal_distance.");
683 
684  camera_set_client.shutdown();
686 
687  // camera_set_fov
688  double fov = 1.33;
689  camera_set_client = n.serviceClient<webots_ros::set_float>(model_name + "/camera/set_fov");
690  webots_ros::set_float camera_set_fov_srv;
691  camera_set_fov_srv.request.value = fov;
692  if (camera_set_client.call(camera_set_fov_srv) && camera_set_fov_srv.response.success)
693  ROS_INFO("Camera fov set to %f.", fov);
694  else
695  ROS_ERROR("Failed to call service camera_set_fov.");
696 
697  camera_set_client.shutdown();
699 
700  // camera enable
701  ros::ServiceClient enable_camera_client;
702  webots_ros::set_int camera_srv;
703  ros::Subscriber sub_camera_color;
704 
705  enable_camera_client = n.serviceClient<webots_ros::set_int>(model_name + "/camera/enable");
706  camera_srv.request.value = TIME_STEP;
707  if (enable_camera_client.call(camera_srv) && camera_srv.response.success) {
708  ROS_INFO("Camera enabled.");
709  sub_camera_color = n.subscribe(model_name + "/camera/image", 1, cameraCallback);
710  ROS_INFO("Topic for camera color initialized.");
711  callbackCalled = false;
712  while (sub_camera_color.getNumPublishers() == 0 && !callbackCalled) {
713  ros::spinOnce();
715  }
716  ROS_INFO("Topic for camera color connected.");
717  } else {
718  if (camera_srv.response.success == -1)
719  ROS_ERROR("Sampling period is not valid.");
720  ROS_ERROR("Failed to enable camera.");
721  return 1;
722  }
723 
724  sub_camera_color.shutdown();
725  enable_camera_client.shutdown();
727 
728  // camera_get_info
729  ros::ServiceClient get_info_client = n.serviceClient<webots_ros::camera_get_info>(model_name + "/camera/get_info");
730  webots_ros::camera_get_info get_info_srv;
731  if (get_info_client.call(get_info_srv))
732  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(),
733  get_info_srv.response.width, get_info_srv.response.height, get_info_srv.response.Fov,
734  get_info_srv.response.nearRange);
735  else
736  ROS_ERROR("Failed to call service camera_get_info.");
737  if (get_info_srv.response.Fov != fov)
738  ROS_ERROR("Failed to set camera fov.");
739 
740  get_info_client.shutdown();
742 
743  // camera_get_focus_info
744  get_info_client = n.serviceClient<webots_ros::camera_get_focus_info>(model_name + "/camera/get_focus_info");
745  webots_ros::camera_get_focus_info camera_get_focus_info_srv;
746  if (get_info_client.call(camera_get_focus_info_srv))
747  ROS_INFO("Camera of %s has focalLength %f, focalDistance %f, maxFocalDistance %f, and minFocalDistance %f.",
748  model_name.c_str(), camera_get_focus_info_srv.response.focalLength,
749  camera_get_focus_info_srv.response.focalDistance, camera_get_focus_info_srv.response.maxFocalDistance,
750  camera_get_focus_info_srv.response.minFocalDistance);
751  else
752  ROS_ERROR("Failed to call service camera_get_focus_info.");
753  if (camera_get_focus_info_srv.response.focalDistance != focal_distance)
754  ROS_ERROR("Failed to set camera focal distance.");
755 
756  get_info_client.shutdown();
758 
759  // camera_get_zoom_info
760  get_info_client = n.serviceClient<webots_ros::camera_get_zoom_info>(model_name + "/camera/get_zoom_info");
761  webots_ros::camera_get_zoom_info camera_get_zoom_info_srv;
762  if (get_info_client.call(camera_get_zoom_info_srv))
763  ROS_INFO("Camera of %s has min fov %f, anf max fov %f.", model_name.c_str(), camera_get_zoom_info_srv.response.minFov,
764  camera_get_zoom_info_srv.response.maxFov);
765  else
766  ROS_ERROR("Failed to call service camera_get_zoom_info.");
767 
768  get_info_client.shutdown();
770 
771  // camera_get_exposure
772  camera_set_client = n.serviceClient<webots_ros::get_float>(model_name + "/camera/get_exposure");
773  webots_ros::get_float camera_get_exposure_srv;
774  if (camera_set_client.call(camera_get_exposure_srv) && camera_get_exposure_srv.response.value == 1.0)
775  ROS_INFO("Camera exposure is %lf.", camera_get_exposure_srv.response.value);
776  else
777  ROS_ERROR("Failed to call service camera_get_exposure.");
778 
779  camera_set_client.shutdown();
781 
782  // camera_set_exposure
783  camera_set_client = n.serviceClient<webots_ros::set_float>(model_name + "/camera/set_exposure");
784  webots_ros::set_float camera_set_exposure_srv;
785  camera_set_exposure_srv.request.value = 1.0;
786  if (camera_set_client.call(camera_set_exposure_srv) && camera_set_exposure_srv.response.success)
787  ROS_INFO("Camera exposure set to %lf.", camera_set_exposure_srv.request.value);
788  else
789  ROS_ERROR("Failed to call service camera_set_exposure.");
790 
791  camera_set_client.shutdown();
793 
794  // check presence of recognition capability
795  get_info_client = n.serviceClient<webots_ros::get_bool>(model_name + "/camera/has_recognition");
796  webots_ros::get_bool camera_has_recognition_srv;
797  if (get_info_client.call(camera_has_recognition_srv))
798  if (camera_has_recognition_srv.response.value)
799  ROS_INFO("Recognition capability of camera of %s found.", model_name.c_str());
800  else
801  ROS_ERROR("Recognition capability of camera of %s not found.", model_name.c_str());
802  else
803  ROS_ERROR("Failed to call service camera_get_zoom_info.");
804 
805  get_info_client.shutdown();
807 
808  // camera recognition enable
809  ros::ServiceClient enable_camera_recognition_client;
810  webots_ros::set_int camera_recognition_srv;
811  ros::Subscriber sub_camera_recognition;
812 
813  enable_camera_recognition_client = n.serviceClient<webots_ros::set_int>(model_name + "/camera/recognition_enable");
814  camera_recognition_srv.request.value = TIME_STEP;
815  if (enable_camera_recognition_client.call(camera_recognition_srv) && camera_recognition_srv.response.success) {
816  ROS_INFO("Camera recognition enabled.");
817  sub_camera_recognition = n.subscribe(model_name + "/camera/recognition_objects", 1, cameraRecognitionCallback);
818  ROS_INFO("Topic for camera recognition initialized.");
819  callbackCalled = false;
820  while (sub_camera_recognition.getNumPublishers() == 0 && !callbackCalled) {
821  ros::spinOnce();
823  }
824  ROS_INFO("Topic for camera recognition connected.");
825  } else {
826  if (camera_recognition_srv.response.success == -1)
827  ROS_ERROR("Sampling period is not valid.");
828  ROS_ERROR("Failed to enable camera recognition.");
829  return 1;
830  }
831 
832  sub_camera_recognition.shutdown();
833  enable_camera_recognition_client.shutdown();
835 
836  // camera recognition segmentation is enabled
837  ros::ServiceClient has_segmentation_client =
838  n.serviceClient<webots_ros::get_bool>(model_name + "/camera/recognition_has_segmentation");
839  webots_ros::get_bool has_segmentation_srv;
840  if (has_segmentation_client.call(has_segmentation_srv)) {
841  if (has_segmentation_srv.response.value)
842  ROS_INFO("Camera recognition segmentation field is TRUE.");
843  else
844  ROS_INFO("Camera recognition segmentation field is FALSE.");
845  } else
846  ROS_ERROR("Failed to get segmentation field value.");
847  has_segmentation_client.shutdown();
848 
849  // camera recognition enable segmentation
850  ros::ServiceClient enable_segmentation_client =
851  n.serviceClient<webots_ros::get_bool>(model_name + "/camera/recognition_enable_segmentation");
852  webots_ros::get_bool enable_segmentation_srv;
853  if (enable_segmentation_client.call(enable_segmentation_srv) && enable_segmentation_srv.response.value)
854  ROS_INFO("Segmentation correctly available.");
855  else {
856  if (!enable_segmentation_srv.response.value)
857  ROS_ERROR("Segmentation value could not be retrieved correctly.");
858  ROS_ERROR("Failed to retrieve segmentation value.");
859  return 1;
860  }
861 
862  enable_segmentation_client.shutdown();
864 
865  ros::ServiceClient is_segmentation_enabled_client =
866  n.serviceClient<webots_ros::get_bool>(model_name + "/camera/recognition_is_segmentation_enabled");
867  webots_ros::get_bool is_segmentation_enabled_srv;
868  if (is_segmentation_enabled_client.call(is_segmentation_enabled_srv) && is_segmentation_enabled_srv.response.value)
869  ROS_INFO("Segmentation correctly enabled.");
870  else {
871  if (!enable_segmentation_srv.response.value)
872  ROS_ERROR("Failed to enable segmentation.");
873  ROS_ERROR("Failed to query segmentation enabled status.");
874  return 1;
875  }
876 
877  is_segmentation_enabled_client.shutdown();
879 
880  ros::Subscriber sub_segmentation =
881  n.subscribe(model_name + "/camera/recognition_segmentation_image", 1, segmentationCallback);
882  ROS_INFO("Topic for camera recognition segmentation initialized.");
883  callbackCalled = false;
884  while (sub_segmentation.getNumPublishers() == 0 && !callbackCalled) {
885  ros::spinOnce();
887  }
888  ROS_INFO("Topic for camera recognition segmentation connected.");
889  sub_segmentation.shutdown();
891 
892  sub_camera_color.shutdown();
893  enable_camera_client.shutdown();
895 
896  // camera recognition save segmentation image
897  ros::ServiceClient save_segmentation_image_client =
898  n.serviceClient<webots_ros::save_image>(model_name + "/camera/recognition_save_segmentation_image");
899  webots_ros::save_image save_segmentation_image_srv;
900  save_segmentation_image_srv.request.filename = std::string(getenv("HOME")) + std::string("/test_image_segmentation.png");
901  save_segmentation_image_srv.request.quality = 100;
902  if (save_segmentation_image_client.call(save_segmentation_image_srv) && save_segmentation_image_srv.response.success == 1)
903  ROS_INFO("Segmentation image saved.");
904  else
905  ROS_ERROR("Failed to call save segmentation image.");
906 
907  // camera recognition disable segmentation
908  ros::ServiceClient disable_segmentation_client =
909  n.serviceClient<webots_ros::get_bool>(model_name + "/camera/recognition_disable_segmentation");
910  webots_ros::get_bool disable_segmentation_srv;
911  if (disable_segmentation_client.call(disable_segmentation_srv) && disable_segmentation_srv.response.value)
912  ROS_INFO("Segmentation correctly disabled.");
913  else {
914  if (!disable_segmentation_srv.response.value)
915  ROS_ERROR("Segmentation value could not be disabled.");
916  ROS_ERROR("Failed to set segmentation.");
917  return 1;
918  }
919 
920  enable_segmentation_client.shutdown();
922 
923  // camera_save_image
924  ros::ServiceClient save_image_client = n.serviceClient<webots_ros::save_image>(model_name + "/camera/save_image");
925  webots_ros::save_image save_image_srv;
926  save_image_srv.request.filename = std::string(getenv("HOME")) + std::string("/test_image_camera.png");
927  save_image_srv.request.quality = 100;
928 
929  if (save_image_client.call(save_image_srv) && save_image_srv.response.success == 1)
930  ROS_INFO("Image saved.");
931  else
932  ROS_ERROR("Failed to call service save_image.");
933 
934  save_image_client.shutdown();
936 
937  ROS_INFO("Camera disabled.");
938 
940  // DEVICE METHODS TEST //
942 
943  // device_get_name
944  ros::ServiceClient device_get_name_client = n.serviceClient<webots_ros::get_string>(model_name + "/camera/get_name");
945  webots_ros::get_string device_get_name_srv;
946  if (device_get_name_client.call(device_get_name_srv))
947  ROS_INFO("Camera device name: %s.", device_get_name_srv.response.value.c_str());
948  else
949  ROS_ERROR("Failed to call service get_name.");
950 
951  device_get_name_client.shutdown();
953 
954  // device_get_name
955  ros::ServiceClient device_get_model_client = n.serviceClient<webots_ros::get_string>(model_name + "/camera/get_model");
956  webots_ros::get_string device_get_model_srv;
957  if (device_get_model_client.call(device_get_model_srv))
958  ROS_INFO("Camera device model: %s.", device_get_model_srv.response.value.c_str());
959  else
960  ROS_ERROR("Failed to call service get_model.");
961 
962  device_get_model_client.shutdown();
964 
966  // ACCELEROMETER METHODS TEST //
968 
969  ros::ServiceClient set_accelerometer_client;
970  webots_ros::set_int accelerometer_srv;
971  ros::Subscriber sub_accelerometer_32;
972  ros::Subscriber sub_accelerometer_64;
973 
974  set_accelerometer_client = n.serviceClient<webots_ros::set_int>(model_name + "/accelerometer/enable");
975 
976  accelerometer_srv.request.value = 64;
977  if (set_accelerometer_client.call(accelerometer_srv) && accelerometer_srv.response.success) {
978  sub_accelerometer_64 = n.subscribe(model_name + "/accelerometer/values", 1, accelerometerCallback);
979  callbackCalled = false;
980  while (sub_accelerometer_64.getNumPublishers() == 0 && !callbackCalled) {
981  ros::spinOnce();
983  }
984  } else {
985  if (accelerometer_srv.response.success == -1)
986  ROS_ERROR("Sampling period is not valid.");
987  ROS_ERROR("Failed to enable accelerometer.");
988  return 1;
989  }
990 
991  sub_accelerometer_64.shutdown();
993 
994  ros::ServiceClient sampling_period_accelerometer_client;
995  webots_ros::get_int sampling_period_accelerometer_srv;
996 
997  sampling_period_accelerometer_client =
998  n.serviceClient<webots_ros::get_int>(model_name + "/accelerometer/get_sampling_period");
999  sampling_period_accelerometer_client.call(sampling_period_accelerometer_srv);
1000  ROS_INFO("Accelerometer is enabled with a sampling period of %d.", sampling_period_accelerometer_srv.response.value);
1001 
1002  accelerometer_srv.request.value = 32;
1003  if (set_accelerometer_client.call(accelerometer_srv) && accelerometer_srv.response.success) {
1004  sub_accelerometer_32 = n.subscribe(model_name + "/accelerometer/values", 1, accelerometerCallback);
1005  callbackCalled = false;
1006  while (sub_accelerometer_32.getNumPublishers() == 0 && !callbackCalled) {
1007  ros::spinOnce();
1009  }
1010  } else {
1011  if (accelerometer_srv.response.success == -1)
1012  ROS_ERROR("Sampling period is not valid.");
1013  ROS_ERROR("Failed to enable accelerometer.");
1014  return 1;
1015  }
1016 
1017  ros::ServiceClient lookup_table_accelerometer_client;
1018  webots_ros::get_float_array lookup_table_accelerometer_srv;
1019  lookup_table_accelerometer_client =
1020  n.serviceClient<webots_ros::get_float_array>(model_name + "/accelerometer/get_lookup_table");
1021  if (lookup_table_accelerometer_client.call(lookup_table_accelerometer_srv))
1022  ROS_INFO("Accelerometer lookup table size = %lu.", lookup_table_accelerometer_srv.response.value.size());
1023  else
1024  ROS_ERROR("Failed to get the lookup table of 'accelerometer'.");
1025  if (lookup_table_accelerometer_srv.response.value.size() != 0)
1026  ROS_ERROR("Size of lookup table of 'accelerometer' is wrong.");
1027  lookup_table_accelerometer_client.shutdown();
1028 
1029  sub_accelerometer_32.shutdown();
1030  set_accelerometer_client.shutdown();
1032 
1033  sampling_period_accelerometer_client.call(sampling_period_accelerometer_srv);
1034  ROS_INFO("Accelerometer is enabled with a sampling period of %d.", sampling_period_accelerometer_srv.response.value);
1035 
1036  // wait for webots to detect shutdown of topics and to disable the sensor afterwards
1040 
1041  sampling_period_accelerometer_client.call(sampling_period_accelerometer_srv);
1042  ROS_INFO("Accelerometer is disabled (sampling period is %d).", sampling_period_accelerometer_srv.response.value);
1043 
1044  sampling_period_accelerometer_client.shutdown();
1046 
1048  // ALTIMETER METHODS TEST //
1050 
1051  ros::ServiceClient set_altimeter_client;
1052  webots_ros::set_int altimeter_srv;
1053  ros::Subscriber sub_altimeter_32;
1054 
1055  set_altimeter_client = n.serviceClient<webots_ros::set_int>(model_name + "/altimeter/enable");
1056 
1057  ros::ServiceClient sampling_period_altimeter_client;
1058  webots_ros::get_int sampling_period_altimeter_srv;
1059  sampling_period_altimeter_client =
1060  n.serviceClient<webots_ros::get_int>(model_name + "/altimeter/get_sampling_period");
1061 
1062  altimeter_srv.request.value = 32;
1063  if (set_altimeter_client.call(altimeter_srv) && altimeter_srv.response.success) {
1064  ROS_INFO("Altimeter enabled.");
1065  sub_altimeter_32 = n.subscribe(model_name + "/altimeter/value", 1, altimeterCallback);
1066  callbackCalled = false;
1067  while (sub_altimeter_32.getNumPublishers() == 0 && !callbackCalled) {
1068  ros::spinOnce();
1070  }
1071  } else {
1072  if (!altimeter_srv.response.success)
1073  ROS_ERROR("Sampling period is not valid.");
1074  ROS_ERROR("Failed to enable altimeter.");
1075  return 1;
1076  }
1077 
1078  sub_altimeter_32.shutdown();
1079 
1081 
1082  sampling_period_altimeter_client.call(sampling_period_altimeter_srv);
1083  ROS_INFO("Altimeter is enabled with a sampling period of %d.", sampling_period_altimeter_srv.response.value);
1084 
1086 
1090 
1091  sampling_period_altimeter_client.call(sampling_period_altimeter_srv);
1092  ROS_INFO("Altimeter is disabled (sampling period is %d).", sampling_period_altimeter_srv.response.value);
1093 
1094  set_altimeter_client.shutdown();
1095  sampling_period_altimeter_client.shutdown();
1097 
1098 
1100  // BATTERY SENSOR METHODS TEST //
1102 
1103  ros::ServiceClient set_battery_sensor_client;
1104  webots_ros::set_int battery_sensor_srv;
1105  ros::Subscriber sub_battery_sensor_32;
1106  set_battery_sensor_client = n.serviceClient<webots_ros::set_int>(model_name + "/battery_sensor/enable");
1107 
1108  ros::ServiceClient sampling_period_battery_sensor_client;
1109  webots_ros::get_int sampling_period_battery_sensor_srv;
1110  sampling_period_battery_sensor_client =
1111  n.serviceClient<webots_ros::get_int>(model_name + "/battery_sensor/get_sampling_period");
1112 
1113  battery_sensor_srv.request.value = 32;
1114  if (set_battery_sensor_client.call(battery_sensor_srv) && battery_sensor_srv.response.success) {
1115  ROS_INFO("Battery_sensor enabled.");
1116  sub_battery_sensor_32 = n.subscribe(model_name + "/battery_sensor/value", 1, battery_sensorCallback);
1117  callbackCalled = false;
1118  while (sub_battery_sensor_32.getNumPublishers() == 0 && !callbackCalled) {
1119  ros::spinOnce();
1121  }
1122  } else {
1123  if (!battery_sensor_srv.response.success)
1124  ROS_ERROR("Sampling period is not valid.");
1125  ROS_ERROR("Failed to enable battery_sensor.");
1126  return 1;
1127  }
1128 
1129  sub_battery_sensor_32.shutdown();
1130 
1132 
1133  sampling_period_battery_sensor_client.call(sampling_period_battery_sensor_srv);
1134  ROS_INFO("Battery_sensor is enabled with a sampling period of %d.", sampling_period_battery_sensor_srv.response.value);
1135 
1137 
1141 
1142  sampling_period_battery_sensor_client.call(sampling_period_battery_sensor_srv);
1143  ROS_INFO("Battery_sensor is disabled (sampling period is %d).", sampling_period_battery_sensor_srv.response.value);
1144 
1145  set_battery_sensor_client.shutdown();
1146  sampling_period_battery_sensor_client.shutdown();
1148 
1150  // COMPASS METHODS TEST //
1152 
1153  ros::ServiceClient set_compass_client;
1154  webots_ros::set_int compass_srv;
1155  ros::Subscriber sub_compass_32;
1156  set_compass_client = n.serviceClient<webots_ros::set_int>(model_name + "/compass/enable");
1157 
1158  ros::ServiceClient sampling_period_compass_client;
1159  webots_ros::get_int sampling_period_compass_srv;
1160  sampling_period_compass_client = n.serviceClient<webots_ros::get_int>(model_name + "/compass/get_sampling_period");
1161 
1162  compass_srv.request.value = 32;
1163  if (set_compass_client.call(compass_srv) && compass_srv.response.success == 1) {
1164  ROS_INFO("Compass enabled.");
1165  sub_compass_32 = n.subscribe(model_name + "/compass/values", 1, compassCallback);
1166  callbackCalled = false;
1167  while (sub_compass_32.getNumPublishers() == 0 && !callbackCalled) {
1168  ros::spinOnce();
1170  }
1171  } else {
1172  if (compass_srv.response.success == -1)
1173  ROS_ERROR("Sampling period is not valid.");
1174  ROS_ERROR("Failed to enable compass.");
1175  return 1;
1176  }
1177 
1178  ros::ServiceClient lookup_table_compass_client;
1179  webots_ros::get_float_array lookup_table_compass_srv;
1180  lookup_table_compass_client = n.serviceClient<webots_ros::get_float_array>(model_name + "/compass/get_lookup_table");
1181  if (lookup_table_compass_client.call(lookup_table_compass_srv))
1182  ROS_INFO("Compass lookup table size = %lu.", lookup_table_compass_srv.response.value.size());
1183  else
1184  ROS_ERROR("Failed to get the lookup table of 'compass'.");
1185  if (lookup_table_compass_srv.response.value.size() != 0)
1186  ROS_ERROR("Size of lookup table of 'compass' is wrong.");
1187  lookup_table_compass_client.shutdown();
1188 
1189  sub_compass_32.shutdown();
1190 
1192 
1193  sampling_period_compass_client.call(sampling_period_compass_srv);
1194  ROS_INFO("Compass is enabled with a sampling period of %d.", sampling_period_compass_srv.response.value);
1195 
1197 
1201 
1202  sampling_period_compass_client.call(sampling_period_compass_srv);
1203  ROS_INFO("Compass is disabled (sampling period is %d).", sampling_period_compass_srv.response.value);
1204 
1205  set_compass_client.shutdown();
1206  sampling_period_compass_client.shutdown();
1208 
1210  // CONNECTOR METHODS TEST //
1212 
1213  ros::ServiceClient connector_enable_presence_client;
1214  webots_ros::set_int connector_srv;
1215  ros::Subscriber sub_connector;
1216  connector_enable_presence_client = n.serviceClient<webots_ros::set_int>(model_name + "/connector/presence_sensor/enable");
1217 
1218  connector_srv.request.value = 32;
1219  if (connector_enable_presence_client.call(connector_srv) && connector_srv.response.success) {
1220  ROS_INFO("Connector's presence sensor enabled.");
1221  sub_connector = n.subscribe(model_name + "/connector/presence", 1, connectorCallback);
1222  callbackCalled = false;
1223  while (sub_connector.getNumPublishers() == 0 && !callbackCalled) {
1224  ros::spinOnce();
1226  }
1227  } else {
1228  if (!connector_srv.response.success)
1229  ROS_ERROR("Sampling period is not valid.");
1230  ROS_ERROR("Failed to enable connector's presence sensor.");
1231  return 1;
1232  }
1233 
1234  sub_connector.shutdown();
1235 
1239 
1240  connector_srv.request.value = 0;
1241  if (connector_enable_presence_client.call(connector_srv) && connector_srv.response.success)
1242  ROS_INFO("Connector's presence sensor disabled.");
1243  else {
1244  if (!connector_srv.response.success)
1245  ROS_ERROR("Sampling period is not valid.");
1246  ROS_ERROR("Failed to disable connector's presence sensor.");
1247  return 1;
1248  }
1249 
1250  ros::ServiceClient connector_lock_client;
1251  webots_ros::set_bool connector_lock_srv;
1252  connector_lock_client = n.serviceClient<webots_ros::set_bool>(model_name + "/connector/lock");
1253 
1254  connector_lock_srv.request.value = true;
1255  if (connector_lock_client.call(connector_lock_srv) && connector_lock_srv.response.success)
1256  ROS_INFO("Connector has been locked.");
1257  else
1258  ROS_INFO("Failed to lock connector.");
1259 
1260  connector_lock_client.shutdown();
1261  connector_enable_presence_client.shutdown();
1263 
1264  ros::ServiceClient connector_is_locked_client;
1265  webots_ros::get_bool connector_is_locked_srv;
1266  connector_is_locked_client = n.serviceClient<webots_ros::get_bool>(model_name + "/connector/is_locked");
1267 
1268  if (connector_is_locked_client.call(connector_is_locked_srv))
1269  ROS_INFO("Connector is locked: %d", connector_is_locked_srv.response.value);
1270  else
1271  ROS_INFO("Failed to call is_locked for connector.");
1272 
1273  connector_lock_client.shutdown();
1274  connector_enable_presence_client.shutdown();
1276 
1278  // DISPLAY METHODS TEST //
1280 
1281  ros::ServiceClient display_get_info_client;
1282  webots_ros::display_get_info display_get_info_srv;
1283  display_get_info_client = n.serviceClient<webots_ros::display_get_info>(model_name + "/display/get_info");
1284 
1285  display_get_info_client.call(display_get_info_srv);
1286  ROS_INFO("Display's width is %d and its height is %d.", display_get_info_srv.response.width,
1287  display_get_info_srv.response.height);
1288 
1289  display_get_info_client.shutdown();
1291 
1292  ros::ServiceClient display_set_color_client;
1293  webots_ros::set_int display_set_color_srv;
1294  display_set_color_client = n.serviceClient<webots_ros::set_int>(model_name + "/display/set_color");
1295 
1296  display_set_color_srv.request.value = 0xFF0000;
1297  if (display_set_color_client.call(display_set_color_srv) && display_set_color_srv.response.success)
1298  ROS_INFO("Display's color has been updated.");
1299  else
1300  ROS_ERROR("Failed to call service display_set_color. Success = %d.", display_set_color_srv.response.success);
1301 
1302  display_set_color_client.shutdown();
1304 
1305  ros::ServiceClient display_set_alpha_client;
1306  webots_ros::set_float display_set_alpha_srv;
1307  display_set_alpha_client = n.serviceClient<webots_ros::set_float>(model_name + "/display/set_alpha");
1308 
1309  display_set_alpha_srv.request.value = 1.0;
1310  if (display_set_alpha_client.call(display_set_alpha_srv) && display_set_alpha_srv.response.success)
1311  ROS_INFO("Display's alpha has been updated.");
1312  else
1313  ROS_ERROR("Failed to call service display_set_alpha.");
1314 
1315  display_set_alpha_client.shutdown();
1317 
1318  ros::ServiceClient display_set_opacity_client;
1319  webots_ros::set_float display_set_opacity_srv;
1320  display_set_opacity_client = n.serviceClient<webots_ros::set_float>(model_name + "/display/set_opacity");
1321 
1322  display_set_opacity_srv.request.value = 1.0;
1323  if (display_set_opacity_client.call(display_set_opacity_srv) && display_set_opacity_srv.response.success)
1324  ROS_INFO("Display's opacity has been updated.");
1325  else
1326  ROS_ERROR("Failed to call service display_set_opacity.");
1327 
1328  display_set_opacity_client.shutdown();
1330 
1331  ros::ServiceClient display_set_font_client;
1332  webots_ros::display_set_font display_set_font_srv;
1333  display_set_font_client = n.serviceClient<webots_ros::display_set_font>(model_name + "/display/set_font");
1334 
1335  display_set_font_srv.request.font = "Arial";
1336  display_set_font_srv.request.size = 8;
1337  display_set_font_srv.request.antiAliasing = 0;
1338  if (display_set_font_client.call(display_set_font_srv) && display_set_font_srv.response.success == 1)
1339  ROS_INFO("Display's font has been updated.");
1340  else
1341  ROS_ERROR("Failed to call service display_set_font. Success = %d.", display_set_font_srv.response.success);
1342 
1343  display_set_font_client.shutdown();
1345 
1346  ros::ServiceClient display_draw_pixel_client;
1347  webots_ros::display_draw_pixel display_draw_pixel_srv;
1348  display_draw_pixel_client = n.serviceClient<webots_ros::display_draw_pixel>(model_name + "/display/draw_pixel");
1349 
1350  display_draw_pixel_srv.request.x1 = 10;
1351  display_draw_pixel_srv.request.y1 = 10;
1352  if (display_draw_pixel_client.call(display_draw_pixel_srv) && display_draw_pixel_srv.response.success == 1)
1353  ROS_INFO("Pixel drawn at x =32 and y = 32 on the display.");
1354  else
1355  ROS_ERROR("Failed to call service display_draw_pixel. Success = %d.", display_draw_pixel_srv.response.success);
1356 
1357  display_draw_pixel_client.shutdown();
1359 
1360  ros::ServiceClient display_draw_line_client;
1361  webots_ros::display_draw_line display_draw_line_srv;
1362  display_draw_line_client = n.serviceClient<webots_ros::display_draw_line>(model_name + "/display/draw_line");
1363 
1364  display_draw_line_srv.request.x1 = 32;
1365  display_draw_line_srv.request.x2 = 63;
1366  display_draw_line_srv.request.y1 = 32;
1367  display_draw_line_srv.request.y2 = 42;
1368  if (display_draw_line_client.call(display_draw_line_srv) && display_draw_line_srv.response.success == 1)
1369  ROS_INFO("Line drawn at x =32 and y = 32 on the display.");
1370  else
1371  ROS_ERROR("Failed to call service display_draw_line. Success = %d.", display_draw_line_srv.response.success);
1372 
1373  display_draw_line_client.shutdown();
1375 
1376  ros::ServiceClient display_draw_rectangle_client;
1377  webots_ros::display_draw_rectangle display_draw_rectangle_srv;
1378  display_draw_rectangle_client = n.serviceClient<webots_ros::display_draw_rectangle>(model_name + "/display/draw_rectangle");
1379 
1380  display_draw_rectangle_srv.request.x = 2;
1381  display_draw_rectangle_srv.request.y = 32;
1382  display_draw_rectangle_srv.request.width = 10;
1383  display_draw_rectangle_srv.request.height = 5;
1384  if (display_draw_rectangle_client.call(display_draw_rectangle_srv) && display_draw_rectangle_srv.response.success == 1)
1385  ROS_INFO("Rectangle drawn at x =32 and y = 32 with width = 10 and height = 5 on the display.");
1386  else
1387  ROS_ERROR("Failed to call service display_draw_rectangle. Success = %d.", display_draw_rectangle_srv.response.success);
1388 
1389  display_draw_rectangle_client.shutdown();
1391 
1392  ros::ServiceClient display_draw_oval_client;
1393  webots_ros::display_draw_oval display_draw_oval_srv;
1394  display_draw_oval_client = n.serviceClient<webots_ros::display_draw_oval>(model_name + "/display/draw_oval");
1395 
1396  display_draw_oval_srv.request.cx = 32;
1397  display_draw_oval_srv.request.cy = 6;
1398  display_draw_oval_srv.request.a = 10;
1399  display_draw_oval_srv.request.b = 5;
1400 
1401  if (display_draw_oval_client.call(display_draw_oval_srv) && display_draw_oval_srv.response.success == 1)
1402  ROS_INFO("Oval drawn at x =32 and y = 6 and axes a = 10 and b = 5 on the display.");
1403  else
1404  ROS_ERROR("Failed to call service display_draw_oval. Success = %d.", display_draw_oval_srv.response.success);
1405 
1406  display_draw_oval_client.shutdown();
1408 
1409  ros::ServiceClient display_draw_polygon_client;
1410  webots_ros::display_draw_polygon display_draw_polygon_srv;
1411  display_draw_polygon_client = n.serviceClient<webots_ros::display_draw_polygon>(model_name + "/display/draw_polygon");
1412 
1413  display_draw_polygon_srv.request.x.push_back(55);
1414  display_draw_polygon_srv.request.y.push_back(55);
1415  display_draw_polygon_srv.request.x.push_back(50);
1416  display_draw_polygon_srv.request.y.push_back(50);
1417  display_draw_polygon_srv.request.x.push_back(45);
1418  display_draw_polygon_srv.request.y.push_back(45);
1419  display_draw_polygon_srv.request.x.push_back(45);
1420  display_draw_polygon_srv.request.y.push_back(55);
1421  display_draw_polygon_srv.request.x.push_back(40);
1422  display_draw_polygon_srv.request.y.push_back(50);
1423  display_draw_polygon_srv.request.size = 5;
1424  if (display_draw_polygon_client.call(display_draw_polygon_srv) && display_draw_polygon_srv.response.success == 1)
1425  ROS_INFO("Polygon drawn on the display.");
1426  else
1427  ROS_ERROR("Failed to call service display_draw_polygon. Success = %d.", display_draw_polygon_srv.response.success);
1428 
1429  display_draw_polygon_client.shutdown();
1431 
1432  ros::ServiceClient display_draw_text_client;
1433  webots_ros::display_draw_text display_draw_text_srv;
1434  display_draw_text_client = n.serviceClient<webots_ros::display_draw_text>(model_name + "/display/draw_text");
1435 
1436  display_draw_text_srv.request.x = 10;
1437  display_draw_text_srv.request.y = 52;
1438  display_draw_text_srv.request.text = "hello world";
1439  if (display_draw_text_client.call(display_draw_text_srv) && display_draw_text_srv.response.success == 1)
1440  ROS_INFO("Hello World written at x =10 and y = 52 on the display.");
1441  else
1442  ROS_ERROR("Failed to call service display_draw_text. Success = %d.", display_draw_text_srv.response.success);
1443 
1444  display_draw_text_client.shutdown();
1446 
1447  ros::ServiceClient display_fill_rectangle_client;
1448  webots_ros::display_draw_rectangle display_fill_rectangle_srv;
1449  display_fill_rectangle_client = n.serviceClient<webots_ros::display_draw_rectangle>(model_name + "/display/fill_rectangle");
1450 
1451  display_fill_rectangle_srv.request.x = 2;
1452  display_fill_rectangle_srv.request.y = 32;
1453  display_fill_rectangle_srv.request.width = 10;
1454  display_fill_rectangle_srv.request.height = 5;
1455  if (display_fill_rectangle_client.call(display_fill_rectangle_srv) && display_fill_rectangle_srv.response.success == 1)
1456  ROS_INFO("Rectangle filled at x =32 and y = 32 with width = 10 and height = 5 on the display.");
1457  else
1458  ROS_ERROR("Failed to call service display_fill_rectangle. Success = %d.", display_fill_rectangle_srv.response.success);
1459 
1460  display_fill_rectangle_client.shutdown();
1462 
1463  ros::ServiceClient display_fill_oval_client;
1464  webots_ros::display_draw_oval display_fill_oval_srv;
1465  display_fill_oval_client = n.serviceClient<webots_ros::display_draw_oval>(model_name + "/display/fill_oval");
1466 
1467  display_fill_oval_srv.request.cx = 32;
1468  display_fill_oval_srv.request.cy = 6;
1469  display_fill_oval_srv.request.a = 10;
1470  display_fill_oval_srv.request.b = 5;
1471 
1472  if (display_fill_oval_client.call(display_fill_oval_srv) && display_fill_oval_srv.response.success == 1)
1473  ROS_INFO("Oval filled at x =32 and y = 6 and axes a = 10 and b = 5 on the display.");
1474  else
1475  ROS_ERROR("Failed to call service display_fill_oval. Success = %d.", display_fill_oval_srv.response.success);
1476 
1477  display_fill_oval_client.shutdown();
1479 
1480  ros::ServiceClient display_fill_polygon_client;
1481  webots_ros::display_draw_polygon display_fill_polygon_srv;
1482  display_fill_polygon_client = n.serviceClient<webots_ros::display_draw_polygon>(model_name + "/display/fill_polygon");
1483 
1484  display_fill_polygon_srv.request.x.push_back(55);
1485  display_fill_polygon_srv.request.y.push_back(55);
1486  display_fill_polygon_srv.request.x.push_back(50);
1487  display_fill_polygon_srv.request.y.push_back(50);
1488  display_fill_polygon_srv.request.x.push_back(45);
1489  display_fill_polygon_srv.request.y.push_back(45);
1490  display_fill_polygon_srv.request.x.push_back(45);
1491  display_fill_polygon_srv.request.y.push_back(55);
1492  display_fill_polygon_srv.request.x.push_back(40);
1493  display_fill_polygon_srv.request.y.push_back(50);
1494  display_fill_polygon_srv.request.size = 5;
1495  if (display_fill_polygon_client.call(display_fill_polygon_srv) && display_fill_polygon_srv.response.success == 1)
1496  ROS_INFO("Polygon filled on the display.");
1497  else
1498  ROS_ERROR("Failed to call service display_fill_polygon. Success = %d.", display_fill_polygon_srv.response.success);
1499 
1500  display_fill_polygon_client.shutdown();
1504 
1505  ros::ServiceClient display_image_new_client;
1506  webots_ros::display_image_new display_image_new_srv;
1507  display_image_new_client = n.serviceClient<webots_ros::display_image_new>(model_name + "/display/image_new");
1508 
1509  display_image_new_srv.request.format = 3;
1510  display_image_new_srv.request.width = 10;
1511  display_image_new_srv.request.height = 5;
1512  display_image_new_srv.request.data.push_back(1);
1513  display_image_new_srv.request.data.push_back(2);
1514  display_image_new_srv.request.data.push_back(5);
1515  display_image_new_srv.request.data.push_back(3);
1516  display_image_new_srv.request.data.push_back(4);
1517  display_image_new_client.call(display_image_new_srv);
1518  ROS_INFO("New image created.");
1519  uint64_t new_image = display_image_new_srv.response.ir;
1520 
1521  display_image_new_client.shutdown();
1523 
1524  ros::ServiceClient display_image_copy_client;
1525  webots_ros::display_image_copy display_image_copy_srv;
1526  display_image_copy_client = n.serviceClient<webots_ros::display_image_copy>(model_name + "/display/image_copy");
1527 
1528  display_image_copy_srv.request.x = 0;
1529  display_image_copy_srv.request.y = 32;
1530  display_image_copy_srv.request.width = 64;
1531  display_image_copy_srv.request.height = 32;
1532  display_image_copy_client.call(display_image_copy_srv);
1533  ROS_INFO("Image copied.");
1534  uint64_t copy_image = display_image_copy_srv.response.ir;
1535 
1536  display_image_copy_client.shutdown();
1538 
1539  ros::ServiceClient display_image_paste_client;
1540  webots_ros::display_image_paste display_image_paste_srv;
1541  display_image_paste_client = n.serviceClient<webots_ros::display_image_paste>(model_name + "/display/image_paste");
1542 
1543  display_image_paste_srv.request.ir = copy_image;
1544  display_image_paste_srv.request.x = 0;
1545  display_image_paste_srv.request.y = 0;
1546  display_image_paste_srv.request.blend = 1;
1547  if (display_image_paste_client.call(display_image_paste_srv) && display_image_paste_srv.response.success == 1)
1548  ROS_INFO("Image successfully copy/paste.");
1549  else
1550  ROS_ERROR("Failed to call service display_image_paste to paste image.");
1551 
1552  display_image_paste_client.shutdown();
1556 
1557  ros::ServiceClient display_image_save_client;
1558  webots_ros::display_image_save display_image_save_srv;
1559  display_image_save_client = n.serviceClient<webots_ros::display_image_save>(model_name + "/display/image_save");
1560 
1561  display_image_save_srv.request.ir = copy_image;
1562  display_image_save_srv.request.filename = std::string(getenv("HOME")) + std::string("/copy_image.png");
1563  if (display_image_save_client.call(display_image_save_srv) && display_image_save_srv.response.success == 1)
1564  ROS_INFO("Image successfully saved.");
1565  else
1566  ROS_ERROR("Failed to call service display_image_save to save image.");
1567 
1568  display_image_save_client.shutdown();
1570 
1571  ros::ServiceClient display_image_load_client;
1572  webots_ros::display_image_load display_image_load_srv;
1573  display_image_load_client = n.serviceClient<webots_ros::display_image_load>(model_name + "/display/image_load");
1574 
1575  display_image_load_srv.request.filename = std::string(getenv("HOME")) + std::string("/test_image_camera.png");
1576  display_image_load_client.call(display_image_load_srv);
1577  ROS_INFO("Image successfully loaded to clipboard.");
1578  uint64_t loaded_image = display_image_load_srv.response.ir;
1579 
1580  display_image_paste_srv.request.ir = loaded_image;
1581  if (display_image_paste_client.call(display_image_paste_srv) && display_image_paste_srv.response.success == 1)
1582  ROS_INFO("Image successfully load and paste.");
1583  else
1584  ROS_ERROR("Failed to call service display_image_paste to paste image.");
1585 
1586  display_image_load_client.shutdown();
1588 
1589  ros::ServiceClient display_image_delete_client;
1590  webots_ros::display_image_delete display_image_delete_srv;
1591  display_image_delete_client = n.serviceClient<webots_ros::display_image_delete>(model_name + "/display/image_delete");
1592 
1593  display_image_delete_srv.request.ir = loaded_image;
1594  if (display_image_delete_client.call(display_image_delete_srv) && display_image_delete_srv.response.success == 1)
1595  ROS_INFO("Loaded image has been deleted.");
1596  else
1597  ROS_ERROR("Failed to call service display_image_delete.");
1598 
1599  display_image_delete_srv.request.ir = copy_image;
1600  if (display_image_delete_client.call(display_image_delete_srv) && display_image_delete_srv.response.success == 1)
1601  ROS_INFO("Copy image has been deleted.");
1602  else
1603  ROS_ERROR("Failed to call service display_image_delete.");
1604 
1605  display_image_delete_srv.request.ir = new_image;
1606  if (display_image_delete_client.call(display_image_delete_srv) && display_image_delete_srv.response.success == 1)
1607  ROS_INFO("New image has been deleted.");
1608  else
1609  ROS_ERROR("Failed to call service display_image_delete.");
1610 
1611  display_image_delete_client.shutdown();
1613 
1615  // DISTANCE SENSOR METHODS TEST //
1617 
1618  ros::ServiceClient set_distance_sensor_client;
1619  webots_ros::set_int distance_sensor_srv;
1620  ros::Subscriber sub_distance_sensor_32;
1621  set_distance_sensor_client = n.serviceClient<webots_ros::set_int>(model_name + "/distance_sensor/enable");
1622 
1623  ros::ServiceClient sampling_period_distance_sensor_client;
1624  webots_ros::get_int sampling_period_distance_sensor_srv;
1625  sampling_period_distance_sensor_client =
1626  n.serviceClient<webots_ros::get_int>(model_name + "/distance_sensor/get_sampling_period");
1627 
1628  ros::ServiceClient min_value_distance_sensor_client;
1629  webots_ros::get_float min_value_distance_sensor_srv;
1630  min_value_distance_sensor_client = n.serviceClient<webots_ros::get_float>(model_name + "/distance_sensor/get_min_value");
1631  if (min_value_distance_sensor_client.call(min_value_distance_sensor_srv))
1632  ROS_INFO("Distance_sensor min value = %g.", min_value_distance_sensor_srv.response.value);
1633  else
1634  ROS_ERROR("Failed to get the minimum value of 'distance_sensor'.");
1635  min_value_distance_sensor_client.shutdown();
1636 
1637  ros::ServiceClient max_value_distance_sensor_client;
1638  webots_ros::get_float max_value_distance_sensor_srv;
1639  max_value_distance_sensor_client = n.serviceClient<webots_ros::get_float>(model_name + "/distance_sensor/get_max_value");
1640  if (max_value_distance_sensor_client.call(max_value_distance_sensor_srv))
1641  ROS_INFO("Distance_sensor max value = %g.", max_value_distance_sensor_srv.response.value);
1642  else
1643  ROS_ERROR("Failed to get the maximum value of 'distance_sensor'.");
1644  max_value_distance_sensor_client.shutdown();
1645 
1646  ros::ServiceClient aperture_distance_sensor_client;
1647  webots_ros::get_float aperture_distance_sensor_srv;
1648  aperture_distance_sensor_client = n.serviceClient<webots_ros::get_float>(model_name + "/distance_sensor/get_aperture");
1649  if (aperture_distance_sensor_client.call(aperture_distance_sensor_srv))
1650  ROS_INFO("Distance_sensor aperture = %g.", aperture_distance_sensor_srv.response.value);
1651  else
1652  ROS_ERROR("Failed to get the aperture of 'distance_sensor'.");
1653  aperture_distance_sensor_client.shutdown();
1654 
1655  ros::ServiceClient lookup_table_distance_sensor_client;
1656  webots_ros::get_float_array lookup_table_distance_sensor_srv;
1657  lookup_table_distance_sensor_client =
1658  n.serviceClient<webots_ros::get_float_array>(model_name + "/distance_sensor/get_lookup_table");
1659  if (lookup_table_distance_sensor_client.call(lookup_table_distance_sensor_srv))
1660  ROS_INFO("Distance_sensor lookup table size = %lu.", lookup_table_distance_sensor_srv.response.value.size());
1661  else
1662  ROS_ERROR("Failed to get the lookup table of 'distance_sensor'.");
1663  if (lookup_table_distance_sensor_srv.response.value.size() != 6)
1664  ROS_ERROR("Size of lookup table of 'distance_sensor' is wrong, expected 0 got %lu.",
1665  lookup_table_distance_sensor_srv.response.value.size());
1666  lookup_table_distance_sensor_client.shutdown();
1667 
1668  distance_sensor_srv.request.value = 32;
1669  if (set_distance_sensor_client.call(distance_sensor_srv) && distance_sensor_srv.response.success) {
1670  ROS_INFO("Distance_sensor enabled.");
1671  sub_distance_sensor_32 = n.subscribe(model_name + "/distance_sensor/value", 1, distance_sensorCallback);
1672  callbackCalled = false;
1673  while (sub_distance_sensor_32.getNumPublishers() == 0 && !callbackCalled) {
1674  ros::spinOnce();
1676  }
1677  } else {
1678  if (!distance_sensor_srv.response.success)
1679  ROS_ERROR("Sampling period is not valid.");
1680  ROS_ERROR("Failed to enable distance_sensor.");
1681  return 1;
1682  }
1683 
1684  sub_distance_sensor_32.shutdown();
1685 
1687 
1688  sampling_period_distance_sensor_client.call(sampling_period_distance_sensor_srv);
1689  ROS_INFO("Distance_sensor is enabled with a sampling period of %d.", sampling_period_distance_sensor_srv.response.value);
1690 
1692 
1696 
1697  sampling_period_distance_sensor_client.call(sampling_period_distance_sensor_srv);
1698  ROS_INFO("Distance_sensor is disabled (sampling period is %d).", sampling_period_distance_sensor_srv.response.value);
1699 
1700  set_distance_sensor_client.shutdown();
1701  sampling_period_distance_sensor_client.shutdown();
1703 
1705  // EMITTER METHODS TEST //
1707 
1708  ros::ServiceClient emitter_send_client;
1709  webots_ros::set_string emitter_send_srv;
1710  emitter_send_client = n.serviceClient<webots_ros::set_string>(model_name + "/emitter/send");
1711 
1712  emitter_send_srv.request.value = "abc";
1713 
1714  if (emitter_send_client.call(emitter_send_srv) && emitter_send_srv.response.success)
1715  ROS_INFO("Emitter has sent data.");
1716  else
1717  ROS_ERROR("Failed to call service emitter_send to send data.");
1718 
1719  emitter_send_client.shutdown();
1721 
1722  ros::ServiceClient emitter_get_buffer_size_client;
1723  webots_ros::get_int emitter_get_buffer_size_srv;
1724  emitter_get_buffer_size_client = n.serviceClient<webots_ros::get_int>(model_name + "/emitter/get_buffer_size");
1725 
1726  emitter_get_buffer_size_client.call(emitter_get_buffer_size_srv);
1727  ROS_INFO("Emitter's buffer is of size %d.", emitter_get_buffer_size_srv.response.value);
1728 
1729  emitter_get_buffer_size_client.shutdown();
1731 
1732  ros::ServiceClient emitter_set_channel_client;
1733  webots_ros::set_int emitter_set_channel_srv;
1734  emitter_set_channel_client = n.serviceClient<webots_ros::set_int>(model_name + "/emitter/set_channel");
1735 
1736  emitter_set_channel_srv.request.value = 1;
1737 
1738  if (emitter_set_channel_client.call(emitter_set_channel_srv) && emitter_set_channel_srv.response.success)
1739  ROS_INFO("Emitter has update the channel.");
1740  else
1741  ROS_ERROR("Failed to call service emitter_set_channel to update channel.");
1742 
1743  emitter_set_channel_client.shutdown();
1745 
1746  ros::ServiceClient emitter_set_range_client;
1747  webots_ros::set_float emitter_set_range_srv;
1748  emitter_set_range_client = n.serviceClient<webots_ros::set_float>(model_name + "/emitter/set_range");
1749 
1750  emitter_set_range_srv.request.value = 50;
1751 
1752  if (emitter_set_range_client.call(emitter_set_range_srv) && emitter_set_range_srv.response.success)
1753  ROS_INFO("Emitter has update the range.");
1754  else
1755  ROS_ERROR("Failed to call service emitter_set_range to update range.");
1756 
1757  emitter_set_range_client.shutdown();
1759 
1760  ros::ServiceClient emitter_get_channel_client;
1761  webots_ros::get_int emitter_get_channel_srv;
1762  emitter_get_channel_client = n.serviceClient<webots_ros::get_int>(model_name + "/emitter/get_channel");
1763 
1764  emitter_get_channel_client.call(emitter_get_channel_srv);
1765  ROS_INFO("Emitter uses channel %d.", emitter_get_channel_srv.response.value);
1766 
1767  emitter_get_channel_client.shutdown();
1769 
1770  ros::ServiceClient emitter_get_range_client;
1771  webots_ros::get_float emitter_get_range_srv;
1772  emitter_get_range_client = n.serviceClient<webots_ros::get_float>(model_name + "/emitter/get_range");
1773 
1774  emitter_get_range_client.call(emitter_get_range_srv);
1775  ROS_INFO("Emitter has a range of %f.", emitter_get_range_srv.response.value);
1776 
1777  emitter_get_range_client.shutdown();
1779 
1781  // GPS METHODS TEST //
1783 
1784  ros::ServiceClient set_GPS_client;
1785  webots_ros::set_int GPS_srv;
1786  ros::Subscriber sub_GPS_32;
1787  ros::Subscriber sub_GPS_speed;
1788  set_GPS_client = n.serviceClient<webots_ros::set_int>(model_name + "/gps/enable");
1789 
1790  ros::ServiceClient sampling_period_GPS_client;
1791  webots_ros::get_int sampling_period_GPS_srv;
1792  sampling_period_GPS_client = n.serviceClient<webots_ros::get_int>(model_name + "/gps/get_sampling_period");
1793 
1794  GPS_srv.request.value = 32;
1795  if (set_GPS_client.call(GPS_srv) && GPS_srv.response.success) {
1796  ROS_INFO("GPS enabled.");
1797  sub_GPS_32 = n.subscribe(model_name + "/gps/values", 1, GPSCallback);
1798  callbackCalled = false;
1799  while (sub_GPS_32.getNumPublishers() == 0 && !callbackCalled) {
1800  ros::spinOnce();
1802  }
1803  sub_GPS_32.shutdown();
1805 
1806  sub_GPS_speed = n.subscribe(model_name + "/gps/speed", 1, GPSSpeedCallback);
1807  callbackCalled = false;
1808  while (sub_GPS_speed.getNumPublishers() == 0 && !callbackCalled) {
1809  ros::spinOnce();
1811  }
1812  } else {
1813  if (!GPS_srv.response.success)
1814  ROS_ERROR("Sampling period is not valid.");
1815  ROS_ERROR("Failed to enable GPS.");
1816  return 1;
1817  }
1818 
1819  sub_GPS_speed.shutdown();
1821 
1822  sampling_period_GPS_client.call(sampling_period_GPS_srv);
1823  ROS_INFO("GPS is enabled with a sampling period of %d.", sampling_period_GPS_srv.response.value);
1824 
1825  ros::ServiceClient gps_get_coordinate_system_client;
1826  webots_ros::get_int gps_get_coordinate_system_srv;
1827  gps_get_coordinate_system_client = n.serviceClient<webots_ros::get_int>(model_name + "/gps/get_coordinate_system");
1828 
1829  gps_get_coordinate_system_client.call(gps_get_coordinate_system_srv);
1830  ROS_INFO("GPS coordinate system type is: %d.", gps_get_coordinate_system_srv.response.value);
1831 
1833 
1834  sampling_period_GPS_client.call(sampling_period_GPS_srv);
1835  ROS_INFO("GPS is disabled (sampling period is %d).", sampling_period_GPS_srv.response.value);
1836 
1837  set_GPS_client.shutdown();
1838  sampling_period_GPS_client.shutdown();
1839  gps_get_coordinate_system_client.shutdown();
1841 
1843  // GYRO METHODS TEST //
1845 
1846  ros::ServiceClient set_gyro_client;
1847  webots_ros::set_int gyro_srv;
1848  ros::Subscriber sub_gyro_32;
1849  set_gyro_client = n.serviceClient<webots_ros::set_int>(model_name + "/gyro/enable");
1850 
1851  ros::ServiceClient sampling_period_gyro_client;
1852  webots_ros::get_int sampling_period_gyro_srv;
1853  sampling_period_gyro_client = n.serviceClient<webots_ros::get_int>(model_name + "/gyro/get_sampling_period");
1854 
1855  gyro_srv.request.value = 32;
1856  if (set_gyro_client.call(gyro_srv) && gyro_srv.response.success) {
1857  ROS_INFO("Gyro enabled.");
1858  sub_gyro_32 = n.subscribe(model_name + "/gyro/values", 1, gyroCallback);
1859  callbackCalled = false;
1860  while (sub_gyro_32.getNumPublishers() == 0 && !callbackCalled) {
1861  ros::spinOnce();
1863  }
1864  } else {
1865  if (!gyro_srv.response.success)
1866  ROS_ERROR("Sampling period is not valid.");
1867  ROS_ERROR("Failed to enable gyro.");
1868  return 1;
1869  }
1870  sub_gyro_32.shutdown();
1871 
1872  ros::ServiceClient lookup_table_gyro_client;
1873  webots_ros::get_float_array lookup_table_gyro_srv;
1874  lookup_table_gyro_client = n.serviceClient<webots_ros::get_float_array>(model_name + "/gyro/get_lookup_table");
1875  if (lookup_table_gyro_client.call(lookup_table_gyro_srv))
1876  ROS_INFO("Gyro lookup table size = %lu.", lookup_table_gyro_srv.response.value.size());
1877  else
1878  ROS_ERROR("Failed to get the lookup table of 'gyro'.");
1879  if (lookup_table_gyro_srv.response.value.size() != 0)
1880  ROS_ERROR("Size of lookup table of 'gyro' is wrong.");
1881  lookup_table_gyro_client.shutdown();
1882 
1884 
1885  sampling_period_gyro_client.call(sampling_period_gyro_srv);
1886  ROS_INFO("Gyro is enabled with a sampling period of %d.", sampling_period_gyro_srv.response.value);
1887 
1889 
1890  sampling_period_gyro_client.call(sampling_period_gyro_srv);
1891  ROS_INFO("Gyro is disabled (sampling period is %d).", sampling_period_gyro_srv.response.value);
1892 
1893  set_gyro_client.shutdown();
1894  sampling_period_gyro_client.shutdown();
1896 
1898  // INERTIAL_UNIT METHODS TEST //
1900 
1901  ros::ServiceClient set_inertial_unit_client;
1902  webots_ros::set_int inertial_unit_srv;
1903  ros::Subscriber sub_inertial_unit_32;
1904  set_inertial_unit_client = n.serviceClient<webots_ros::set_int>(model_name + "/inertial_unit/enable");
1905 
1906  ros::ServiceClient sampling_period_inertial_unit_client;
1907  webots_ros::get_int sampling_period_inertial_unit_srv;
1908  sampling_period_inertial_unit_client =
1909  n.serviceClient<webots_ros::get_int>(model_name + "/inertial_unit/get_sampling_period");
1910 
1911  inertial_unit_srv.request.value = 32;
1912  if (set_inertial_unit_client.call(inertial_unit_srv) && inertial_unit_srv.response.success) {
1913  ROS_INFO("Inertial_unit enabled.");
1914  sub_inertial_unit_32 = n.subscribe(model_name + "/inertial_unit/quaternion", 1, inertialUnitCallback);
1915  callbackCalled = false;
1916  while (sub_inertial_unit_32.getNumPublishers() == 0 && !callbackCalled) {
1917  ros::spinOnce();
1919  }
1920  } else {
1921  if (!inertial_unit_srv.response.success)
1922  ROS_ERROR("Sampling period is not valid.");
1923  ROS_ERROR("Failed to enable inertial_unit.");
1924  return 1;
1925  }
1926 
1927  sub_inertial_unit_32.shutdown();
1928 
1929  ros::ServiceClient noise_inertial_unit_client;
1930  webots_ros::get_float noise_inertial_unit_srv;
1931  noise_inertial_unit_client = n.serviceClient<webots_ros::get_float>(model_name + "/inertial_unit/get_noise");
1932  if (noise_inertial_unit_client.call(noise_inertial_unit_srv))
1933  ROS_INFO("Noise value is %f.", noise_inertial_unit_srv.response.value);
1934  else
1935  ROS_ERROR("Failed to get noise value for 'inertial_unit'.");
1936  noise_inertial_unit_client.shutdown();
1937 
1939 
1940  sampling_period_inertial_unit_client.call(sampling_period_inertial_unit_srv);
1941  ROS_INFO("Inertial_unit is enabled with a sampling period of %d.", sampling_period_inertial_unit_srv.response.value);
1942 
1944 
1945  sampling_period_inertial_unit_client.call(sampling_period_inertial_unit_srv);
1946  ROS_INFO("Inertial_unit is disabled (sampling period is %d).", sampling_period_inertial_unit_srv.response.value);
1947 
1948  set_inertial_unit_client.shutdown();
1949  sampling_period_inertial_unit_client.shutdown();
1951 
1953  // JOYSTICK METHODS TEST //
1955 
1956  ros::ServiceClient enable_joystick_client = n.serviceClient<webots_ros::set_int>(model_name + "/joystick/enable");
1957  webots_ros::set_int enable_joystick_srv;
1958  ros::Subscriber sub_joystick;
1959 
1960  enable_joystick_srv.request.value = 32;
1961  if (enable_joystick_client.call(enable_joystick_srv) && enable_joystick_srv.response.success) {
1962  ROS_INFO("Joystick of %s has been enabled.", model_name.c_str());
1963  sub_joystick = n.subscribe(model_name + "/joystick/pressed_button", 1, joystickCallback);
1964  callbackCalled = false;
1965  ROS_INFO("Topics for joystick initialized.");
1966 
1967  while (sub_joystick.getNumPublishers() == 0 && !callbackCalled) {
1968  ros::spinOnce();
1970  }
1971  ROS_INFO("Topics for joystick connected.");
1972  } else
1973  ROS_ERROR("Failed to enable joystick.");
1974 
1975  sub_joystick.shutdown();
1976 
1977  enable_joystick_client.shutdown();
1979 
1980  ros::ServiceClient joystick_get_model_client;
1981  webots_ros::get_string joystick_get_model_srv;
1982  joystick_get_model_client = n.serviceClient<webots_ros::get_string>(model_name + "/joystick/get_model");
1983  joystick_get_model_client.call(joystick_get_model_srv);
1984  ROS_INFO("Got josytick model: %s.", joystick_get_model_srv.response.value.c_str());
1985 
1986  joystick_get_model_client.shutdown();
1988 
1990  // LED METHODS TEST //
1992 
1993  ros::ServiceClient set_led_client;
1994  webots_ros::set_int set_led_srv;
1995  set_led_client = n.serviceClient<webots_ros::set_int>(model_name + "/led/set_led");
1996 
1997  set_led_srv.request.value = 1;
1998  if (set_led_client.call(set_led_srv) && set_led_srv.response.success)
1999  ROS_INFO("LED set to 1.");
2000  else
2001  ROS_ERROR("Failed to call service set_led.");
2002 
2003  enable_joystick_client.shutdown();
2004  set_led_client.call(time_step_srv);
2005 
2006  ros::ServiceClient get_led_client;
2007  webots_ros::get_int get_led_srv;
2008  get_led_client = n.serviceClient<webots_ros::get_int>(model_name + "/led/get_led");
2009 
2010  get_led_client.call(get_led_srv);
2011  ROS_INFO("LED value is %d.", get_led_srv.response.value);
2012 
2013  set_led_srv.request.value = 0;
2014  if (set_led_client.call(set_led_srv) && set_led_srv.response.success)
2015  ROS_INFO("LED set to 0.");
2016  else
2017  ROS_ERROR("Failed to call service set_led.");
2018 
2019  set_led_client.shutdown();
2020  get_led_client.shutdown();
2022 
2024  // LIDAR METHODS TEST //
2026 
2027  // lidar enable
2028  ros::ServiceClient set_lidar_client;
2029  webots_ros::set_int lidar_srv;
2030  ros::Subscriber sub_lidar;
2031 
2032  set_lidar_client = n.serviceClient<webots_ros::set_int>(model_name + "/lidar/enable");
2033  lidar_srv.request.value = TIME_STEP;
2034  if (set_lidar_client.call(lidar_srv) && lidar_srv.response.success) {
2035  ROS_INFO("Lidar enabled.");
2036  sub_lidar = n.subscribe(model_name + "/lidar/range_image", 1, lidarCallback);
2037  callbackCalled = false;
2038  ROS_INFO("Topic for lidar initialized.");
2039 
2040  while (sub_lidar.getNumPublishers() == 0 && !callbackCalled) {
2041  ros::spinOnce();
2043  }
2044  ROS_INFO("Topic for lidar color connected.");
2045  } else {
2046  if (!lidar_srv.response.success)
2047  ROS_ERROR("Sampling period is not valid.");
2048  ROS_ERROR("Failed to enable lidar.");
2049  return 1;
2050  }
2051 
2052  sub_lidar.shutdown();
2053  set_lidar_client.shutdown();
2055 
2056  // lidar_get_info
2057  get_info_client = n.serviceClient<webots_ros::lidar_get_info>(model_name + "/lidar/get_info");
2058  webots_ros::lidar_get_info get_lidar_info_srv;
2059  if (get_info_client.call(get_lidar_info_srv))
2060  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 "
2061  "range of %f.",
2062  model_name.c_str(), get_lidar_info_srv.response.horizontalResolution, get_lidar_info_srv.response.numberOfLayers,
2063  get_lidar_info_srv.response.fov, get_lidar_info_srv.response.minRange, get_lidar_info_srv.response.maxRange);
2064  else
2065  ROS_ERROR("Failed to call service lidar_get_info.");
2066 
2067  get_info_client.shutdown();
2069 
2070  // lidar_get_frequency_info
2071  get_info_client = n.serviceClient<webots_ros::lidar_get_frequency_info>(model_name + "/lidar/get_frequency_info");
2072  webots_ros::lidar_get_frequency_info get_lidar_frequency_info_srv;
2073  if (get_info_client.call(get_lidar_frequency_info_srv))
2074  ROS_INFO("Lidar %s current frequency is %f, maximum frequency is %f and minimum frequency is %f.", model_name.c_str(),
2075  get_lidar_frequency_info_srv.response.frequency, get_lidar_frequency_info_srv.response.maxFrequency,
2076  get_lidar_frequency_info_srv.response.minFrequency);
2077  else
2078  ROS_ERROR("Failed to call service lidar_get_frequency_info.");
2079 
2080  get_info_client.shutdown();
2082 
2083  ROS_INFO("Lidar disabled.");
2084 
2086  // LIGHT SENSOR METHODS TEST //
2088 
2089  ros::ServiceClient set_light_sensor_client;
2090  webots_ros::set_int light_sensor_srv;
2091  ros::Subscriber sub_light_sensor_32;
2092  set_light_sensor_client = n.serviceClient<webots_ros::set_int>(model_name + "/light_sensor/enable");
2093 
2094  ros::ServiceClient sampling_period_light_sensor_client;
2095  webots_ros::get_int sampling_period_light_sensor_srv;
2096  sampling_period_light_sensor_client = n.serviceClient<webots_ros::get_int>(model_name + "/light_sensor/get_sampling_period");
2097 
2098  light_sensor_srv.request.value = 32;
2099  if (set_light_sensor_client.call(light_sensor_srv) && light_sensor_srv.response.success) {
2100  ROS_INFO("Light_sensor enabled.");
2101  sub_light_sensor_32 = n.subscribe(model_name + "/light_sensor/value", 1, lightSensorCallback);
2102  callbackCalled = false;
2103  while (sub_light_sensor_32.getNumPublishers() == 0 && !callbackCalled) {
2104  ros::spinOnce();
2106  }
2107  } else {
2108  if (!light_sensor_srv.response.success)
2109  ROS_ERROR("Sampling period is not valid.");
2110  ROS_ERROR("Failed to enable light_sensor.");
2111  return 1;
2112  }
2113 
2114  sub_light_sensor_32.shutdown();
2115 
2116  ros::ServiceClient lookup_table_light_sensor_client;
2117  webots_ros::get_float_array lookup_table_light_sensor_srv;
2118  lookup_table_light_sensor_client =
2119  n.serviceClient<webots_ros::get_float_array>(model_name + "/light_sensor/get_lookup_table");
2120  if (lookup_table_light_sensor_client.call(lookup_table_light_sensor_srv))
2121  ROS_INFO("Light sensor lookup table size = %lu.", lookup_table_light_sensor_srv.response.value.size());
2122  else
2123  ROS_ERROR("Failed to get the lookup table of 'light_sensor'.");
2124  if (lookup_table_light_sensor_srv.response.value.size() != 6)
2125  ROS_ERROR("Size of lookup table of 'light_sensor' is wrong.");
2126  lookup_table_light_sensor_client.shutdown();
2127 
2129 
2130  sampling_period_light_sensor_client.call(sampling_period_light_sensor_srv);
2131  ROS_INFO("Light_sensor is enabled with a sampling period of %d.", sampling_period_light_sensor_srv.response.value);
2132 
2134 
2135  sampling_period_light_sensor_client.call(sampling_period_light_sensor_srv);
2136  ROS_INFO("Light_sensor is disabled (sampling period is %d).", sampling_period_light_sensor_srv.response.value);
2137 
2138  set_light_sensor_client.shutdown();
2139  sampling_period_light_sensor_client.shutdown();
2141 
2143  // MOTOR METHODS TEST //
2145 
2146  ros::ServiceClient motor_get_type_client;
2147  webots_ros::get_int motor_get_type_srv;
2148  motor_get_type_client = n.serviceClient<webots_ros::get_int>(model_name + "/rotational_motor/get_type");
2149  motor_get_type_client.call(motor_get_type_srv);
2150  ROS_INFO("Rotational_motor is of type %d.", motor_get_type_srv.response.value);
2151 
2152  motor_get_type_client.shutdown();
2154 
2155  ros::ServiceClient linear_motor_get_type_client;
2156  webots_ros::get_int linear_motor_get_type_srv;
2157  linear_motor_get_type_client = n.serviceClient<webots_ros::get_int>(model_name + "/linear_motor/get_type");
2158  linear_motor_get_type_client.call(linear_motor_get_type_srv);
2159  ROS_INFO("Linear_motor is of type %d.", linear_motor_get_type_srv.response.value);
2160 
2161  linear_motor_get_type_client.shutdown();
2163 
2164  // motor_get_brake_name
2165  ros::ServiceClient motor_get_brake_name_client;
2166  webots_ros::get_string motor_get_brake_name_srv;
2167  motor_get_brake_name_client = n.serviceClient<webots_ros::get_string>(model_name + "/linear_motor/get_brake_name");
2168  if (motor_get_brake_name_client.call(motor_get_brake_name_srv)) {
2169  ROS_INFO("Brake name returned from Motor API: %s.", motor_get_brake_name_srv.response.value.c_str());
2170  if (motor_get_brake_name_srv.response.value.compare("my_brake") != 0)
2171  ROS_ERROR("Failed to call service motor_get_brake_name: received '%s' instead of 'my_brake'",
2172  motor_get_brake_name_srv.response.value.c_str());
2173  } else
2174  ROS_ERROR("Failed to call service motor_get_brake_name.");
2175 
2176  motor_get_brake_name_client.shutdown();
2178 
2179  ros::ServiceClient set_acceleration_client;
2180  webots_ros::set_float set_acceleration_srv;
2181  set_acceleration_client = n.serviceClient<webots_ros::set_float>(model_name + "/rotational_motor/set_acceleration");
2182 
2183  set_acceleration_srv.request.value = 0.5;
2184  if (set_acceleration_client.call(set_acceleration_srv) && set_acceleration_srv.response.success)
2185  ROS_INFO("Acceleration set to 0.5.");
2186  else
2187  ROS_ERROR("Failed to call service set_acceleration on motor.");
2188 
2189  set_acceleration_client.shutdown();
2191 
2192  ros::ServiceClient set_velocity_client;
2193  webots_ros::set_float set_velocity_srv;
2194  set_velocity_client = n.serviceClient<webots_ros::set_float>(model_name + "/rotational_motor/set_velocity");
2195 
2196  set_velocity_srv.request.value = 0.9;
2197  if (set_velocity_client.call(set_velocity_srv) && set_velocity_srv.response.success)
2198  ROS_INFO("Velocity set to 0.9.");
2199  else
2200  ROS_ERROR("Failed to call service set_velocity on motor.");
2201 
2202  set_velocity_client.shutdown();
2204 
2205  ros::ServiceClient set_force_client;
2206  webots_ros::set_float set_force_srv;
2207  set_force_client = n.serviceClient<webots_ros::set_float>(model_name + "/linear_motor/set_force");
2208 
2209  set_force_srv.request.value = 0.2;
2210  if (set_force_client.call(set_force_srv) && set_force_srv.response.success)
2211  ROS_INFO("Force set to 0.2.");
2212  else
2213  ROS_ERROR("Failed to call service set_force on motor.");
2214 
2215  set_force_client.shutdown();
2217 
2218  ros::ServiceClient set_torque_client;
2219  webots_ros::set_float set_torque_srv;
2220  set_torque_client = n.serviceClient<webots_ros::set_float>(model_name + "/rotational_motor/set_torque");
2221 
2222  set_torque_srv.request.value = 0.5;
2223  if (set_torque_client.call(set_torque_srv) && set_torque_srv.response.success)
2224  ROS_INFO("Torque set to 0.5.");
2225  else
2226  ROS_ERROR("Failed to call service set_torque on motor.");
2227 
2228  set_torque_client.shutdown();
2230 
2231  ros::ServiceClient set_available_force_client;
2232  webots_ros::set_float set_available_force_srv;
2233  set_available_force_client = n.serviceClient<webots_ros::set_float>(model_name + "/linear_motor/set_available_force");
2234 
2235  set_available_force_srv.request.value = 0.8;
2236  if (set_available_force_client.call(set_available_force_srv) && set_available_force_srv.response.success)
2237  ROS_INFO("Available_force set to 0.8.");
2238  else
2239  ROS_ERROR("Failed to call service set_available_force on motor.");
2240 
2241  set_available_force_client.shutdown();
2243 
2244  ros::ServiceClient set_available_torque_client;
2245  webots_ros::set_float set_available_torque_srv;
2246  set_available_torque_client = n.serviceClient<webots_ros::set_float>(model_name + "/rotational_motor/set_available_torque");
2247 
2248  set_available_torque_srv.request.value = 0.8;
2249  if (set_available_torque_client.call(set_available_torque_srv) && set_available_torque_srv.response.success)
2250  ROS_INFO("Available_torque set to 0.8.");
2251  else
2252  ROS_ERROR("Failed to call service set_available_torque on motor.");
2253 
2254  set_available_torque_client.shutdown();
2256 
2257  ros::ServiceClient set_control_pid_client;
2258  webots_ros::motor_set_control_pid set_control_pid_srv;
2259  set_control_pid_client = n.serviceClient<webots_ros::motor_set_control_pid>(model_name + "/rotational_motor/set_control_pid");
2260 
2261  set_control_pid_srv.request.controlp = 1;
2262  if (set_control_pid_client.call(set_control_pid_srv) && set_control_pid_srv.response.success == 1)
2263  ROS_INFO("Control p set to 1.");
2264  else
2265  ROS_ERROR("Failed to call service set_controlp on motor.");
2266 
2267  set_control_pid_client.shutdown();
2270 
2271  ros::ServiceClient set_linear_control_pid_client;
2272  webots_ros::motor_set_control_pid set_linear_control_pid_srv;
2273  set_linear_control_pid_client =
2274  n.serviceClient<webots_ros::motor_set_control_pid>(model_name + "/linear_motor/set_control_pid");
2275 
2276  set_linear_control_pid_srv.request.controlp = 1;
2277  if (set_linear_control_pid_client.call(set_linear_control_pid_srv) && set_linear_control_pid_srv.response.success == 1)
2278  ROS_INFO("Control p set to 1 for linear_motor.");
2279  else
2280  ROS_ERROR("Failed to call service set_controlp on linear_motor.");
2281 
2282  set_linear_control_pid_client.shutdown();
2285 
2286  ros::ServiceClient set_position_client;
2287  webots_ros::set_float set_position_srv;
2288  set_position_client = n.serviceClient<webots_ros::set_float>(model_name + "/rotational_motor/set_position");
2289 
2290  set_position_srv.request.value = 1.5;
2291  if (set_position_client.call(set_position_srv) && set_position_srv.response.success)
2292  ROS_INFO("Position set to 1.5.");
2293  else
2294  ROS_ERROR("Failed to call service set_position on motor.");
2295 
2296  set_position_client.shutdown();
2299 
2300  ros::ServiceClient set_linear_position_client;
2301  webots_ros::set_float set_linear_position_srv;
2302  set_linear_position_client = n.serviceClient<webots_ros::set_float>(model_name + "/linear_motor/set_position");
2303 
2304  set_linear_position_srv.request.value = 0.3;
2305  if (set_linear_position_client.call(set_linear_position_srv) && set_linear_position_srv.response.success)
2306  ROS_INFO("Position set to 0.3 for linear_motor.");
2307  else
2308  ROS_ERROR("Failed to call service set_position on linear_motor.");
2309 
2310  set_linear_position_client.shutdown();
2312 
2313  ros::ServiceClient get_target_position_client;
2314  webots_ros::get_float get_target_position_srv;
2315  get_target_position_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_target_position");
2316 
2317  get_target_position_client.call(get_target_position_srv);
2318  ROS_INFO("Target position for rotational_motor is %f.", get_target_position_srv.response.value);
2319 
2320  get_target_position_client.shutdown();
2322 
2323  ros::ServiceClient get_min_position_client;
2324  webots_ros::get_float get_min_position_srv;
2325  get_min_position_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_min_position");
2326 
2327  get_min_position_client.call(get_min_position_srv);
2328  ROS_INFO("Min position for rotational_motor is %f.", get_min_position_srv.response.value);
2329 
2330  get_min_position_client.shutdown();
2332 
2333  ros::ServiceClient get_max_position_client;
2334  webots_ros::get_float get_max_position_srv;
2335  get_max_position_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_max_position");
2336 
2337  get_max_position_client.call(get_max_position_srv);
2338  ROS_INFO("Max position for rotational_motor is %f.", get_max_position_srv.response.value);
2339 
2340  get_max_position_client.shutdown();
2342 
2343  ros::ServiceClient get_velocity_client;
2344  webots_ros::get_float get_velocity_srv;
2345  get_velocity_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_velocity");
2346 
2347  get_velocity_client.call(get_velocity_srv);
2348  ROS_INFO("Velocity for rotational_motor is %f.", get_velocity_srv.response.value);
2349 
2350  get_velocity_client.shutdown();
2352 
2353  ros::ServiceClient get_max_velocity_client;
2354  webots_ros::get_float get_max_velocity_srv;
2355  get_max_velocity_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_max_velocity");
2356 
2357  get_max_velocity_client.call(get_max_velocity_srv);
2358  ROS_INFO("Max velocity for rotational_motor is %f.", get_max_velocity_srv.response.value);
2359 
2360  get_max_velocity_client.shutdown();
2362 
2363  ros::ServiceClient get_acceleration_client;
2364  webots_ros::get_float get_acceleration_srv;
2365  get_acceleration_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_acceleration");
2366 
2367  get_acceleration_client.call(get_acceleration_srv);
2368  ROS_INFO("Acceleration for rotational_motor is %f.", get_acceleration_srv.response.value);
2369 
2370  get_acceleration_client.shutdown();
2372 
2373  ros::ServiceClient get_available_force_client;
2374  webots_ros::get_float get_available_force_srv;
2375  get_available_force_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_available_force");
2376 
2377  get_available_force_client.call(get_available_force_srv);
2378  ROS_INFO("Available force for rotational_motor is %f.", get_available_force_srv.response.value);
2379 
2380  get_available_force_client.shutdown();
2382 
2383  ros::ServiceClient get_max_force_client;
2384  webots_ros::get_float get_max_force_srv;
2385  get_max_force_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_max_force");
2386 
2387  get_max_force_client.call(get_max_force_srv);
2388  ROS_INFO("Max force for rotational_motor is %f.", get_max_force_srv.response.value);
2389 
2390  get_max_force_client.shutdown();
2392 
2393  ros::ServiceClient get_available_torque_client;
2394  webots_ros::get_float get_available_torque_srv;
2395  get_available_torque_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_available_torque");
2396 
2397  get_available_torque_client.call(get_available_torque_srv);
2398  ROS_INFO("Available torque for rotational_motor is %f.", get_available_torque_srv.response.value);
2399 
2400  get_available_torque_client.shutdown();
2402 
2403  ros::ServiceClient get_max_torque_client;
2404  webots_ros::get_float get_max_torque_srv;
2405  get_max_torque_client = n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_max_torque");
2406 
2407  get_max_torque_client.call(get_max_torque_srv);
2408  ROS_INFO("Max torque for rotational_motor is %f.", get_max_torque_srv.response.value);
2409 
2410  get_max_torque_client.shutdown();
2412 
2413  ros::ServiceClient rotational_motor_get_multiplier_client;
2414  webots_ros::get_float get_multiplier_srv;
2415  rotational_motor_get_multiplier_client =
2416  n.serviceClient<webots_ros::get_float>(model_name + "/rotational_motor/get_multiplier");
2417 
2418  rotational_motor_get_multiplier_client.call(get_multiplier_srv);
2419  ROS_INFO("Multiplier for rotational_motor is %f.", get_multiplier_srv.response.value);
2420 
2421  rotational_motor_get_multiplier_client.shutdown();
2423 
2424  ros::ServiceClient linear_motor_get_multiplier_client;
2425  linear_motor_get_multiplier_client = n.serviceClient<webots_ros::get_float>(model_name + "/linear_motor/get_multiplier");
2426 
2427  linear_motor_get_multiplier_client.call(get_multiplier_srv);
2428  ROS_INFO("Multiplier for linear_motor is %f.", get_multiplier_srv.response.value);
2429 
2430  linear_motor_get_multiplier_client.shutdown();
2432 
2433  ros::ServiceClient set_motor_feedback_client;
2434  webots_ros::set_int motor_feedback_srv;
2435  ros::Subscriber sub_motor_feedback_32;
2436  set_motor_feedback_client =
2437  n.serviceClient<webots_ros::set_int>(model_name + "/rotational_motor/torque_feedback_sensor/enable");
2438 
2439  ros::ServiceClient sampling_period_motor_feedback_client;
2440  webots_ros::get_int sampling_period_motor_feedback_srv;
2441  sampling_period_motor_feedback_client =
2442  n.serviceClient<webots_ros::get_int>(model_name + "/rotational_motor/torque_feedback_sensor/get_sampling_period");
2443 
2444  motor_feedback_srv.request.value = 32;
2445  if (set_motor_feedback_client.call(motor_feedback_srv) && motor_feedback_srv.response.success) {
2446  ROS_INFO("Motor feedback enabled.");
2447  sub_motor_feedback_32 = n.subscribe(model_name + "/rotational_motor/torque_feedback", 1, motorSensorCallback);
2448  callbackCalled = false;
2449  while (sub_motor_feedback_32.getNumPublishers() == 0 && !callbackCalled) {
2450  ros::spinOnce();
2452  }
2453  } else {
2454  if (!motor_feedback_srv.response.success)
2455  ROS_ERROR("Sampling period is not valid.");
2456  ROS_ERROR("Failed to enable motor_feedback.");
2457  return 1;
2458  }
2459 
2460  sub_motor_feedback_32.shutdown();
2461 
2463 
2464  sampling_period_motor_feedback_client.call(sampling_period_motor_feedback_srv);
2465  ROS_INFO("Motor feedback is enabled with a sampling period of %d.", sampling_period_motor_feedback_srv.response.value);
2466 
2468 
2469  sampling_period_motor_feedback_client.call(sampling_period_motor_feedback_srv);
2470  ROS_INFO("Motor feedback is disabled (sampling period is %d).", sampling_period_motor_feedback_srv.response.value);
2471 
2472  set_motor_feedback_client.shutdown();
2473  sampling_period_motor_feedback_client.shutdown();
2476 
2478  // PEN METHODS TEST //
2480 
2481  ros::ServiceClient set_ink_color_client;
2482  webots_ros::pen_set_ink_color set_ink_color_srv;
2483  set_ink_color_client = n.serviceClient<webots_ros::pen_set_ink_color>(model_name + "/pen/set_ink_color");
2484 
2485  set_ink_color_srv.request.color = 0x00FF08;
2486  if (set_ink_color_client.call(set_ink_color_srv) && set_ink_color_srv.response.success == 1)
2487  ROS_INFO("Ink color set to turquoise.");
2488  else
2489  ROS_ERROR("Failed to call service set_ink_color.");
2490 
2491  set_ink_color_client.shutdown();
2493 
2494  ros::ServiceClient pen_write_client;
2495  webots_ros::set_bool pen_write_srv;
2496  pen_write_client = n.serviceClient<webots_ros::set_bool>(model_name + "/pen/write");
2497 
2498  pen_write_srv.request.value = true;
2499  if (pen_write_client.call(pen_write_srv) && pen_write_srv.response.success)
2500  ROS_INFO("Pen is now writing.");
2501  else
2502  ROS_ERROR("Failed to call service pen_write.");
2503 
2504  pen_write_client.shutdown();
2507 
2509  // POSITION SENSOR METHODS TEST //
2511 
2512  ros::ServiceClient set_position_sensor_client;
2513  webots_ros::set_int position_sensor_srv;
2514  ros::Subscriber sub_position_sensor_32;
2515  set_position_sensor_client = n.serviceClient<webots_ros::set_int>(model_name + "/position_sensor/enable");
2516 
2517  ros::ServiceClient sampling_period_position_sensor_client;
2518  webots_ros::get_int sampling_period_position_sensor_srv;
2519  sampling_period_position_sensor_client =
2520  n.serviceClient<webots_ros::get_int>(model_name + "/position_sensor/get_sampling_period");
2521 
2522  position_sensor_srv.request.value = 32;
2523  if (set_position_sensor_client.call(position_sensor_srv) && position_sensor_srv.response.success) {
2524  ROS_INFO("Position_sensor enabled.");
2525  sub_position_sensor_32 = n.subscribe(model_name + "/position_sensor/value", 1, positionSensorCallback);
2526  callbackCalled = false;
2527  while (sub_position_sensor_32.getNumPublishers() == 0 && !callbackCalled) {
2528  ros::spinOnce();
2530  }
2531  } else {
2532  if (!position_sensor_srv.response.success)
2533  ROS_ERROR("Sampling period is not valid.");
2534  ROS_ERROR("Failed to enable position_sensor.");
2535  return 1;
2536  }
2537 
2538  sub_position_sensor_32.shutdown();
2539 
2541 
2542  sampling_period_position_sensor_client.call(sampling_period_position_sensor_srv);
2543  ROS_INFO("Position_sensor is enabled with a sampling period of %d.", sampling_period_position_sensor_srv.response.value);
2544 
2546 
2547  ros::ServiceClient position_sensor_get_type_client;
2548  webots_ros::get_int position_sensor_get_type_srv;
2549  position_sensor_get_type_client = n.serviceClient<webots_ros::get_int>(model_name + "/position_sensor/get_type");
2550 
2551  position_sensor_get_type_client.call(position_sensor_get_type_srv);
2552  ROS_INFO("Position_sensor is of type %d.", position_sensor_get_type_srv.response.value);
2553 
2554  position_sensor_get_type_client.shutdown();
2556 
2557  sampling_period_position_sensor_client.call(sampling_period_position_sensor_srv);
2558  ROS_INFO("Position_sensor is disabled (sampling period is %d).", sampling_period_position_sensor_srv.response.value);
2559 
2560  set_position_sensor_client.shutdown();
2561  sampling_period_position_sensor_client.shutdown();
2563 
2565  // RADAR METHODS TEST //
2567 
2568  // radar enable
2569  ros::ServiceClient set_radar_client;
2570  webots_ros::set_int radar_srv;
2571  ros::Subscriber sub_radar_target;
2572  ros::Subscriber sub_radar_target_number;
2573 
2574  set_radar_client = n.serviceClient<webots_ros::set_int>(model_name + "/radar/enable");
2575  radar_srv.request.value = TIME_STEP;
2576  if (set_radar_client.call(radar_srv) && radar_srv.response.success) {
2577  ROS_INFO("Radar enabled.");
2578  sub_radar_target = n.subscribe(model_name + "/radar/targets", 1, radarTargetsCallback);
2579  sub_radar_target_number = n.subscribe(model_name + "/radar/number_of_targets", 1, radarTargetsNumberCallback);
2580  callbackCalled = false;
2581  ROS_INFO("Topics for radar initialized.");
2582 
2583  while (sub_radar_target.getNumPublishers() == 0 && sub_radar_target_number.getNumPublishers() == 0 && !callbackCalled) {
2584  ros::spinOnce();
2586  }
2587  ROS_INFO("Topics for radar connected.");
2588  } else {
2589  if (!radar_srv.response.success)
2590  ROS_ERROR("Sampling period is not valid.");
2591  ROS_ERROR("Failed to enable radar.");
2592  return 1;
2593  }
2594 
2595  sub_radar_target.shutdown();
2596  sub_radar_target_number.shutdown();
2597  set_radar_client.shutdown();
2599 
2600  // get max and min range
2601  ros::ServiceClient radar_range_client = n.serviceClient<webots_ros::get_float>(model_name + "/radar/get_max_range");
2602  webots_ros::get_float radar_get_max_range_srv;
2603  if (radar_range_client.call(radar_get_max_range_srv)) {
2604  if (radar_get_max_range_srv.response.value == 2.0)
2605  ROS_INFO("Received correct radar max range.");
2606  else
2607  ROS_ERROR("Received wrong radar max range.");
2608  } else
2609  ROS_ERROR("Failed to call service radar_get_max_range.");
2610 
2611  radar_range_client.shutdown();
2613 
2614  radar_range_client = n.serviceClient<webots_ros::get_float>(model_name + "/radar/get_min_range");
2615  webots_ros::get_float radar_get_min_range_srv;
2616  if (radar_range_client.call(radar_get_min_range_srv)) {
2617  if (radar_get_min_range_srv.response.value == 1.0)
2618  ROS_INFO("Received correct radar min range.");
2619  else
2620  ROS_ERROR("Received wrong radar min range.");
2621  } else
2622  ROS_ERROR("Failed to call service radar_get_min_range.");
2623 
2624  radar_range_client.shutdown();
2626 
2627  ROS_INFO("Radar disabled.");
2628 
2630  // RANGE-FINDER METHODS TEST //
2632 
2633  // range-finder enable
2634  ros::ServiceClient set_range_finder_client;
2635  webots_ros::set_int range_finder_srv;
2636  ros::Subscriber sub_range_finder_color;
2637 
2638  set_range_finder_client = n.serviceClient<webots_ros::set_int>(model_name + "/range_finder/enable");
2639  range_finder_srv.request.value = TIME_STEP;
2640  if (set_range_finder_client.call(range_finder_srv) && range_finder_srv.response.success) {
2641  ROS_INFO("Range-finder enabled.");
2642  sub_range_finder_color = n.subscribe(model_name + "/range_finder/range_image", 1, rangeFinderCallback);
2643  callbackCalled = false;
2644  ROS_INFO("Topic for range-finder initialized.");
2645 
2646  while (sub_range_finder_color.getNumPublishers() == 0 && !callbackCalled) {
2647  ros::spinOnce();
2649  }
2650  ROS_INFO("Topic for range-finder connected.");
2651  } else {
2652  if (!range_finder_srv.response.success)
2653  ROS_ERROR("Sampling period is not valid.");
2654  ROS_ERROR("Failed to enable range-finder.");
2655  return 1;
2656  }
2657 
2658  sub_range_finder_color.shutdown();
2659  set_range_finder_client.shutdown();
2661 
2662  // range_finder_get_info
2663  get_info_client = n.serviceClient<webots_ros::range_finder_get_info>(model_name + "/range_finder/get_info");
2664  webots_ros::range_finder_get_info get_range_finder_info_srv;
2665  if (get_info_client.call(get_range_finder_info_srv))
2666  ROS_INFO(
2667  "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.",
2668  model_name.c_str(), get_range_finder_info_srv.response.width, get_range_finder_info_srv.response.height,
2669  get_range_finder_info_srv.response.Fov, get_range_finder_info_srv.response.minRange,
2670  get_range_finder_info_srv.response.maxRange);
2671  else
2672  ROS_ERROR("Failed to call service range_finder_get_info.");
2673 
2674  get_info_client.shutdown();
2676 
2677  // range_finder_save_image
2678  save_image_client = n.serviceClient<webots_ros::save_image>(model_name + "/range_finder/save_image");
2679  webots_ros::save_image save_range_image_srv;
2680  save_range_image_srv.request.filename = std::string(getenv("HOME")) + std::string("/test_image_range_finder.png");
2681  save_range_image_srv.request.quality = 100;
2682 
2683  if (save_image_client.call(save_range_image_srv) && save_range_image_srv.response.success == 1)
2684  ROS_INFO("Image saved.");
2685  else
2686  ROS_ERROR("Failed to call service save_image.");
2687 
2688  save_image_client.shutdown();
2690 
2691  ROS_INFO("Range-finder disabled.");
2692 
2694  // RECEIVER METHODS TEST //
2696 
2697  ros::ServiceClient set_receiver_client;
2698  webots_ros::set_int receiver_srv;
2699  ros::Subscriber sub_receiver_32;
2700  set_receiver_client = n.serviceClient<webots_ros::set_int>(model_name + "/receiver/enable");
2701 
2702  ros::ServiceClient sampling_period_receiver_client;
2703  webots_ros::get_int sampling_period_receiver_srv;
2704  sampling_period_receiver_client = n.serviceClient<webots_ros::get_int>(model_name + "/receiver/get_sampling_period");
2705 
2706  receiver_srv.request.value = 32;
2707  if (set_receiver_client.call(receiver_srv) && receiver_srv.response.success) {
2708  ROS_INFO("Receiver enabled.");
2709  sub_receiver_32 = n.subscribe(model_name + "/receiver/data", 1, receiverCallback);
2710  callbackCalled = false;
2711  while (sub_receiver_32.getNumPublishers() == 0 && !callbackCalled) {
2712  ros::spinOnce();
2714  }
2715  } else {
2716  if (!receiver_srv.response.success)
2717  ROS_ERROR("Sampling period is not valid.");
2718  ROS_ERROR("Failed to enable receiver.");
2719  return 1;
2720  }
2721 
2722  sub_receiver_32.shutdown();
2723  set_receiver_client.shutdown();
2725 
2726  sampling_period_receiver_client.call(sampling_period_receiver_srv);
2727  ROS_INFO("Receiver is enabled with a sampling period of %d.", sampling_period_receiver_srv.response.value);
2728 
2731 
2732  // test receiver_get_data_size
2733  // An error message will probably appear since no data has been sent to the receiver.
2734  ros::ServiceClient receiver_get_data_size_client;
2735  webots_ros::get_int receiver_get_data_size_srv;
2736  receiver_get_data_size_client = n.serviceClient<webots_ros::get_int>(model_name + "/receiver/get_data_size");
2737 
2738  receiver_get_data_size_client.call(receiver_get_data_size_srv);
2739  if (receiver_get_data_size_srv.response.value != -1)
2740  ROS_INFO("Emitter's buffer is of size %d.", receiver_get_data_size_srv.response.value);
2741  else
2742  ROS_INFO("No message received by emitter, impossible to get buffer size.");
2743 
2744  receiver_get_data_size_client.shutdown();
2747 
2748  ros::ServiceClient receiver_set_channel_client;
2749  webots_ros::set_int receiver_set_channel_srv;
2750  receiver_set_channel_client = n.serviceClient<webots_ros::set_int>(model_name + "/receiver/set_channel");
2751 
2752  receiver_set_channel_srv.request.value = 1;
2753 
2754  if (receiver_set_channel_client.call(receiver_set_channel_srv) && receiver_set_channel_srv.response.success)
2755  ROS_INFO("Receiver has update the channel.");
2756  else
2757  ROS_ERROR("Failed to call service receiver_set_channel to update channel.");
2758 
2759  receiver_set_channel_client.shutdown();
2761 
2762  // test receiver_get_channel
2763  ros::ServiceClient receiver_get_channel_client;
2764  webots_ros::get_int receiver_get_channel_srv;
2765  receiver_get_channel_client = n.serviceClient<webots_ros::get_int>(model_name + "/receiver/get_channel");
2766 
2767  receiver_get_channel_client.call(receiver_get_channel_srv);
2768  ROS_INFO("Receiver uses channel %d.", receiver_get_channel_srv.response.value);
2769 
2770  receiver_get_channel_client.shutdown();
2772 
2773  // test receiver_get_queue_length
2774  ros::ServiceClient receiver_get_queue_length_client;
2775  webots_ros::get_int receiver_get_queue_length_srv;
2776  receiver_get_queue_length_client = n.serviceClient<webots_ros::get_int>(model_name + "/receiver/get_queue_length");
2777 
2778  receiver_get_queue_length_client.call(receiver_get_queue_length_srv);
2779  ROS_INFO("Length of receiver queue is %d.", receiver_get_queue_length_srv.response.value);
2780 
2781  receiver_get_queue_length_client.shutdown();
2783 
2784  // test receiver_get_signal_strength
2785  // An error message will probably appear since no signal has been sent to the receiver.
2786  ros::ServiceClient receiver_get_signal_strength_client;
2787  webots_ros::get_float receiver_get_signal_strength_srv;
2788  receiver_get_signal_strength_client = n.serviceClient<webots_ros::get_float>(model_name + "/receiver/get_signal_strength");
2789 
2790  receiver_get_signal_strength_client.call(receiver_get_signal_strength_srv);
2791  if (receiver_get_signal_strength_srv.response.value != -1.0)
2792  ROS_INFO("Strength of the signal is %lf.", receiver_get_signal_strength_srv.response.value);
2793  else
2794  ROS_INFO("No message received by emitter, impossible to get signal strength.");
2795 
2796  receiver_get_signal_strength_client.shutdown();
2798 
2799  // test receiver_get_emitter_direction
2800  // An error message will probably appear since no signal has been sent to the receiver
2801  ros::ServiceClient receiver_get_emitter_direction_client;
2802  webots_ros::receiver_get_emitter_direction receiver_get_emitter_direction_srv;
2803  receiver_get_emitter_direction_client =
2804  n.serviceClient<webots_ros::receiver_get_emitter_direction>(model_name + "/receiver/get_emitter_direction");
2805 
2806  receiver_get_emitter_direction_client.call(receiver_get_emitter_direction_srv);
2807  if (receiver_get_emitter_direction_srv.response.direction[0] != 0 ||
2808  receiver_get_emitter_direction_srv.response.direction[1] != 0 ||
2809  receiver_get_emitter_direction_srv.response.direction[2] != 0)
2810  ROS_INFO("Signal from emitter comes from direction {%f. %f, %f}.", receiver_get_emitter_direction_srv.response.direction[0],
2811  receiver_get_emitter_direction_srv.response.direction[1],
2812  receiver_get_emitter_direction_srv.response.direction[2]);
2813  else
2814  ROS_INFO("No message received by emitter, impossible to get signal direction.");
2815 
2816  receiver_get_emitter_direction_client.shutdown();
2818 
2819  // test receiver_next_packet
2820  // An error message will probably appear since there is no packet to read
2821  ros::ServiceClient receiver_next_packet_client;
2822  webots_ros::get_bool receiver_next_packet_srv;
2823  receiver_next_packet_client = n.serviceClient<webots_ros::get_bool>(model_name + "/receiver/next_packet");
2824 
2825  if (receiver_next_packet_client.call(receiver_next_packet_srv) && receiver_next_packet_srv.response.value)
2826  ROS_INFO("Next packet is ready to be read.");
2827  else if (!receiver_next_packet_srv.response.value)
2828  ROS_INFO("No message received by emitter, impossible to get next packet.");
2829  else
2830  ROS_ERROR("Failed to call service receiver_next_packet.");
2831 
2832  receiver_next_packet_client.shutdown();
2834 
2835  sampling_period_receiver_client.call(sampling_period_receiver_srv);
2836  ROS_INFO("Receiver is disabled (sampling period is %d).", sampling_period_receiver_srv.response.value);
2837 
2838  sampling_period_receiver_client.shutdown();
2840 
2842  // TOUCH SENSOR METHODS TEST //
2844 
2845  ros::ServiceClient set_touch_sensor_client;
2846  webots_ros::set_int touch_sensor_srv;
2847  ros::Subscriber sub_touch_sensor_32;
2848  set_touch_sensor_client = n.serviceClient<webots_ros::set_int>(model_name + "/touch_sensor/enable");
2849 
2850  ros::ServiceClient sampling_period_touch_sensor_client;
2851  webots_ros::get_int sampling_period_touch_sensor_srv;
2852  sampling_period_touch_sensor_client = n.serviceClient<webots_ros::get_int>(model_name + "/touch_sensor/get_sampling_period");
2853 
2854  ros::ServiceClient touch_sensor_get_type_client;
2855  webots_ros::get_int touch_sensor_get_type_srv;
2856  touch_sensor_get_type_client = n.serviceClient<webots_ros::get_int>(model_name + "/touch_sensor/get_type");
2857 
2858  touch_sensor_get_type_client.call(touch_sensor_get_type_srv);
2859  ROS_INFO("Touch_sensor is of type %d.", touch_sensor_get_type_srv.response.value);
2860 
2861  touch_sensor_get_type_client.shutdown();
2863 
2864  touch_sensor_srv.request.value = 32;
2865  if (set_touch_sensor_client.call(touch_sensor_srv) && touch_sensor_srv.response.success) {
2866  ROS_INFO("Touch_sensor enabled.");
2867  if (touch_sensor_get_type_srv.response.value == 0)
2868  sub_touch_sensor_32 = n.subscribe(model_name + "/touch_sensor/value", 1, touchSensorBumperCallback);
2869  else if (touch_sensor_get_type_srv.response.value == 1)
2870  sub_touch_sensor_32 = n.subscribe(model_name + "/touch_sensor/value", 1, touchSensorCallback);
2871  else
2872  sub_touch_sensor_32 = n.subscribe(model_name + "/touch_sensor/values", 1, touchSensor3DCallback);
2873  callbackCalled = false;
2874  while (sub_touch_sensor_32.getNumPublishers() == 0 && !callbackCalled) {
2875  ros::spinOnce();
2877  }
2878  } else {
2879  if (!touch_sensor_srv.response.success)
2880  ROS_ERROR("Sampling period is not valid.");
2881  ROS_ERROR("Failed to enable touch_sensor.");
2882  return 1;
2883  }
2884 
2885  sub_touch_sensor_32.shutdown();
2886 
2887  ros::ServiceClient lookup_table_touch_sensor_client;
2888  webots_ros::get_float_array lookup_table_touch_sensor_srv;
2889  lookup_table_touch_sensor_client =
2890  n.serviceClient<webots_ros::get_float_array>(model_name + "/touch_sensor/get_lookup_table");
2891  if (lookup_table_touch_sensor_client.call(lookup_table_touch_sensor_srv))
2892  ROS_INFO("Touch sensor lookup table size = %lu.", lookup_table_touch_sensor_srv.response.value.size());
2893  else
2894  ROS_ERROR("Failed to get the lookup table of 'touch_sensor'.");
2895  if (lookup_table_touch_sensor_srv.response.value.size() != 6)
2896  ROS_ERROR("Size of lookup table of 'touch_sensor' is wrong.");
2897  lookup_table_touch_sensor_client.shutdown();
2898 
2900 
2901  sampling_period_touch_sensor_client.call(sampling_period_touch_sensor_srv);
2902  ROS_INFO("Touch_sensor is enabled with a sampling period of %d.", sampling_period_touch_sensor_srv.response.value);
2903 
2905 
2906  sampling_period_touch_sensor_client.call(sampling_period_touch_sensor_srv);
2907  ROS_INFO("Touch_sensor is disabled (sampling period is %d).", sampling_period_touch_sensor_srv.response.value);
2908 
2909  set_touch_sensor_client.shutdown();
2910  sampling_period_touch_sensor_client.shutdown();
2912 
2914  // SUPERVISOR METHODS TEST //
2916 
2917  ros::ServiceClient supervisor_simulation_reset_physics_client;
2918  webots_ros::get_bool supervisor_simulation_reset_physics_srv;
2919  supervisor_simulation_reset_physics_client =
2920  n.serviceClient<webots_ros::get_bool>(model_name + "/supervisor/simulation_reset_physics");
2921 
2922  if (supervisor_simulation_reset_physics_client.call(supervisor_simulation_reset_physics_srv) &&
2923  supervisor_simulation_reset_physics_srv.response.value)
2924  ROS_INFO("Simulation has reset_physics successfully.");
2925  else
2926  ROS_ERROR("Failed to call service simulation_reset_physics.");
2927 
2928  supervisor_simulation_reset_physics_client.shutdown();
2930 
2931  ros::ServiceClient supervisor_export_image_client;
2932  webots_ros::save_image supervisor_export_image_srv;
2933  supervisor_export_image_client = n.serviceClient<webots_ros::save_image>(model_name + "/supervisor/export_image");
2934 
2935  supervisor_export_image_srv.request.filename = std::string(getenv("HOME")) + std::string("/main_window_test.jpg");
2936  supervisor_export_image_srv.request.quality = 100;
2937  if (supervisor_export_image_client.call(supervisor_export_image_srv) && supervisor_export_image_srv.response.success == 1)
2938  ROS_INFO("Image from main window saved successfully.");
2939  else
2940  ROS_ERROR("Failed to call service export_image.");
2941 
2942  supervisor_export_image_client.shutdown();
2944 
2945  ros::ServiceClient supervisor_set_label_client;
2946  webots_ros::supervisor_set_label supervisor_set_label_srv;
2947  supervisor_set_label_client = n.serviceClient<webots_ros::supervisor_set_label>(model_name + "/supervisor/set_label");
2948 
2949  supervisor_set_label_srv.request.id = 1;
2950  supervisor_set_label_srv.request.label = "This is a label";
2951  supervisor_set_label_srv.request.xpos = 0.02;
2952  supervisor_set_label_srv.request.ypos = 0.2;
2953  supervisor_set_label_srv.request.size = 0.1;
2954  supervisor_set_label_srv.request.color = 0XFF0000;
2955  supervisor_set_label_srv.request.transparency = 0;
2956  supervisor_set_label_srv.request.font = "Lucida Console";
2957  if (supervisor_set_label_client.call(supervisor_set_label_srv) && supervisor_set_label_srv.response.success == 1)
2958  ROS_INFO("Label set successfully.");
2959  else
2960  ROS_ERROR("Failed to call service set_label.");
2961 
2963 
2964  ros::ServiceClient supervisor_get_root_client;
2965  webots_ros::get_uint64 supervisor_get_root_srv;
2966  supervisor_get_root_client = n.serviceClient<webots_ros::get_uint64>(model_name + "/supervisor/get_root");
2967 
2968  supervisor_get_root_client.call(supervisor_get_root_srv);
2969  ROS_INFO("Got root node: %lu.", supervisor_get_root_srv.response.value);
2970  uint64_t root_node = supervisor_get_root_srv.response.value;
2971 
2972  supervisor_get_root_client.shutdown();
2974 
2975  ros::ServiceClient supervisor_get_self_client;
2976  webots_ros::get_uint64 supervisor_get_self_srv;
2977  supervisor_get_self_client = n.serviceClient<webots_ros::get_uint64>(model_name + "/supervisor/get_self");
2978 
2979  supervisor_get_self_client.call(supervisor_get_self_srv);
2980  ROS_INFO("Got self node: %lu.", supervisor_get_self_srv.response.value);
2981  uint64_t self_node = supervisor_get_self_srv.response.value;
2982 
2983  supervisor_get_self_client.shutdown();
2985 
2986  ros::ServiceClient supervisor_get_from_def_client;
2987  webots_ros::supervisor_get_from_def supervisor_get_from_def_srv;
2988  supervisor_get_from_def_client =
2989  n.serviceClient<webots_ros::supervisor_get_from_def>(model_name + "/supervisor/get_from_def");
2990 
2991  supervisor_get_from_def_srv.request.name = "TEST";
2992  supervisor_get_from_def_client.call(supervisor_get_from_def_srv);
2993  uint64_t from_def_node = 0;
2994  if (supervisor_get_from_def_srv.response.node != 0) {
2995  ROS_INFO("Got from DEF node: %ld.", supervisor_get_from_def_srv.response.node);
2996  from_def_node = supervisor_get_from_def_srv.response.node;
2997  } else
2998  ROS_ERROR("Could not get node from DEF.");
2999 
3001 
3002  ros::ServiceClient supervisor_node_get_type_client;
3003  webots_ros::node_get_type supervisor_node_get_type_srv;
3004  supervisor_node_get_type_client = n.serviceClient<webots_ros::node_get_type>(model_name + "/supervisor/node/get_type");
3005 
3006  supervisor_node_get_type_srv.request.node = from_def_node;
3007  supervisor_node_get_type_client.call(supervisor_node_get_type_srv);
3008  ROS_INFO("Got node type: %d.", supervisor_node_get_type_srv.response.type);
3009 
3010  supervisor_node_get_type_client.shutdown();
3012 
3013  ros::ServiceClient supervisor_node_get_type_name_client;
3014  webots_ros::node_get_name supervisor_node_get_type_name_srv;
3015  supervisor_node_get_type_name_client =
3016  n.serviceClient<webots_ros::node_get_name>(model_name + "/supervisor/node/get_type_name");
3017 
3018  supervisor_node_get_type_name_srv.request.node = from_def_node;
3019  supervisor_node_get_type_name_client.call(supervisor_node_get_type_name_srv);
3020  ROS_INFO("Got node type name: %s.", supervisor_node_get_type_name_srv.response.name.c_str());
3021 
3022  supervisor_node_get_type_name_srv.request.node = root_node;
3023  supervisor_node_get_type_name_client.call(supervisor_node_get_type_name_srv);
3024  ROS_INFO("Got type name of root node: %s.", supervisor_node_get_type_name_srv.response.name.c_str());
3025 
3026  supervisor_node_get_type_name_srv.request.node = self_node;
3027  supervisor_node_get_type_name_client.call(supervisor_node_get_type_name_srv);
3028  ROS_INFO("Got type name of self node: %s.", supervisor_node_get_type_name_srv.response.name.c_str());
3029 
3030  supervisor_get_from_def_srv.request.name = "GROUND";
3031  supervisor_get_from_def_client.call(supervisor_get_from_def_srv);
3032  uint64_t ground_node = 0;
3033  if (supervisor_get_from_def_srv.response.node != 0) {
3034  ROS_INFO("Got from DEF GROUND node: %ld.", supervisor_get_from_def_srv.response.node);
3035  ground_node = supervisor_get_from_def_srv.response.node;
3036  } else
3037  ROS_ERROR("Could not get node from DEF GROUND.");
3038 
3039  supervisor_node_get_type_name_srv.request.node = ground_node;
3040  supervisor_node_get_type_name_client.call(supervisor_node_get_type_name_srv);
3041  ROS_INFO("Got type name of GROUND node: %s.", supervisor_node_get_type_name_srv.response.name.c_str());
3042 
3044 
3045  ros::ServiceClient supervisor_node_get_base_type_name_client;
3046  webots_ros::node_get_name supervisor_node_get_base_type_name_srv;
3047  supervisor_node_get_base_type_name_client =
3048  n.serviceClient<webots_ros::node_get_name>(model_name + "/supervisor/node/get_base_type_name");
3049  supervisor_node_get_base_type_name_srv.request.node = ground_node;
3050  supervisor_node_get_base_type_name_client.call(supervisor_node_get_base_type_name_srv);
3051  ROS_INFO("Got base type name of GROUND node: %s.", supervisor_node_get_base_type_name_srv.response.name.c_str());
3052 
3053  supervisor_node_get_base_type_name_client.shutdown();
3055 
3056  ros::ServiceClient supervisor_node_get_def_client;
3057  webots_ros::node_get_name supervisor_node_get_def_srv;
3058  supervisor_node_get_def_client = n.serviceClient<webots_ros::node_get_name>(model_name + "/supervisor/node/get_def");
3059  supervisor_node_get_def_srv.request.node = ground_node;
3060  supervisor_node_get_def_client.call(supervisor_node_get_def_srv);
3061  ROS_INFO("Got DEF name of GROUND node: %s.", supervisor_node_get_def_srv.response.name.c_str());
3062 
3063  supervisor_node_get_def_client.shutdown();
3065 
3066  ros::ServiceClient supervisor_node_get_position_client;
3067  webots_ros::node_get_position supervisor_node_get_position_srv;
3068  supervisor_node_get_position_client =
3069  n.serviceClient<webots_ros::node_get_position>(model_name + "/supervisor/node/get_position");
3070 
3071  supervisor_node_get_position_srv.request.node = from_def_node;
3072  supervisor_node_get_position_client.call(supervisor_node_get_position_srv);
3073  ROS_INFO("From_def node got position: x = %f y = %f z = %f.", supervisor_node_get_position_srv.response.position.x,
3074  supervisor_node_get_position_srv.response.position.y, supervisor_node_get_position_srv.response.position.z);
3075 
3076  supervisor_node_get_position_client.shutdown();
3078 
3079  // supervisor_node_get_orientation
3080  ros::ServiceClient supervisor_node_get_orientation_client;
3081  webots_ros::node_get_orientation supervisor_node_get_orientation_srv;
3082  supervisor_node_get_orientation_client =
3083  n.serviceClient<webots_ros::node_get_orientation>(model_name + "/supervisor/node/get_orientation");
3084 
3085  supervisor_node_get_orientation_srv.request.node = from_def_node;
3086  supervisor_node_get_orientation_client.call(supervisor_node_get_orientation_srv);
3087  ROS_INFO(
3088  "From_def orientation quaternion is:\nw=%f x=%f y=%f z=%f.", supervisor_node_get_orientation_srv.response.orientation.w,
3089  supervisor_node_get_orientation_srv.response.orientation.x, supervisor_node_get_orientation_srv.response.orientation.y,
3090  supervisor_node_get_orientation_srv.response.orientation.z);
3091 
3092  supervisor_node_get_orientation_client.shutdown();
3094 
3095  // supervisor_node_get_pose
3096  ros::ServiceClient supervisor_node_get_pose_client;
3097  webots_ros::node_get_pose supervisor_node_get_pose_srv;
3098  supervisor_node_get_pose_client = n.serviceClient<webots_ros::node_get_pose>(model_name + "/supervisor/node/get_pose");
3099 
3100  supervisor_node_get_pose_srv.request.from_node = from_def_node;
3101  supervisor_node_get_pose_srv.request.node = from_def_node;
3102  supervisor_node_get_pose_client.call(supervisor_node_get_pose_srv);
3103  ROS_INFO("From_def get_pose rotation is:\nw=%f x=%f y=%f z=%f.", supervisor_node_get_pose_srv.response.pose.rotation.w,
3104  supervisor_node_get_pose_srv.response.pose.rotation.x, supervisor_node_get_pose_srv.response.pose.rotation.y,
3105  supervisor_node_get_pose_srv.response.pose.rotation.z);
3106  ROS_INFO("From_def get_pose translation is:\nx=%f y=%f z=%f.", supervisor_node_get_pose_srv.response.pose.translation.x,
3107  supervisor_node_get_pose_srv.response.pose.translation.y, supervisor_node_get_pose_srv.response.pose.translation.z);
3108 
3109  supervisor_node_get_pose_client.shutdown();
3111 
3112  // supervisor_node_enable_pose_tracking
3113  ros::ServiceClient supervisor_node_enable_pose_tracking_client;
3114  webots_ros::node_enable_pose_tracking supervisor_node_enable_pose_tracking_srv;
3115  supervisor_node_enable_pose_tracking_client =
3116  n.serviceClient<webots_ros::node_enable_pose_tracking>(model_name + "/supervisor/node/enable_pose_tracking");
3117 
3118  supervisor_node_enable_pose_tracking_srv.request.from_node = from_def_node;
3119  supervisor_node_enable_pose_tracking_srv.request.node = from_def_node;
3120  supervisor_node_enable_pose_tracking_srv.request.sampling_period = 32;
3121  supervisor_node_enable_pose_tracking_client.call(supervisor_node_enable_pose_tracking_srv);
3122  supervisor_node_enable_pose_tracking_client.shutdown();
3124 
3125  // supervisor_node_disable_pose_tracking
3126  ros::ServiceClient supervisor_node_disable_pose_tracking_client;
3127  webots_ros::node_disable_pose_tracking supervisor_node_disable_pose_tracking_srv;
3128  supervisor_node_disable_pose_tracking_client =
3129  n.serviceClient<webots_ros::node_disable_pose_tracking>(model_name + "/supervisor/node/disable_pose_tracking");
3130 
3131  supervisor_node_disable_pose_tracking_srv.request.from_node = from_def_node;
3132  supervisor_node_disable_pose_tracking_srv.request.node = from_def_node;
3133  supervisor_node_disable_pose_tracking_client.call(supervisor_node_disable_pose_tracking_srv);
3134  supervisor_node_disable_pose_tracking_client.shutdown();
3136 
3137  // supervisor_node_get_center_of_mass
3138  ros::ServiceClient supervisor_node_get_center_of_mass_client;
3139  webots_ros::node_get_center_of_mass supervisor_node_get_center_of_mass_srv;
3140  supervisor_node_get_center_of_mass_client =
3141  n.serviceClient<webots_ros::node_get_center_of_mass>(model_name + "/supervisor/node/get_center_of_mass");
3142 
3143  supervisor_node_get_center_of_mass_srv.request.node = from_def_node;
3144  supervisor_node_get_center_of_mass_client.call(supervisor_node_get_center_of_mass_srv);
3145  ROS_INFO("From_def node's center of mass coordinates are: x = %f y = %f z = %f.",
3146  supervisor_node_get_center_of_mass_srv.response.centerOfMass.x,
3147  supervisor_node_get_center_of_mass_srv.response.centerOfMass.y,
3148  supervisor_node_get_center_of_mass_srv.response.centerOfMass.z);
3149 
3150  supervisor_node_get_center_of_mass_client.shutdown();
3152 
3153  ros::ServiceClient supervisor_node_get_number_of_contact_points_client;
3154  webots_ros::node_get_number_of_contact_points supervisor_node_get_number_of_contact_points_srv;
3155  supervisor_node_get_number_of_contact_points_client = n.serviceClient<webots_ros::node_get_number_of_contact_points>(
3156  model_name + "/supervisor/node/get_number_of_contact_points");
3157 
3158  supervisor_node_get_number_of_contact_points_srv.request.node = from_def_node;
3159  supervisor_node_get_number_of_contact_points_srv.request.includeDescendants = false;
3160  supervisor_node_get_number_of_contact_points_client.call(supervisor_node_get_number_of_contact_points_srv);
3161  ROS_INFO("From_def node got %d contact points.",
3162  supervisor_node_get_number_of_contact_points_srv.response.numberOfContactPoints);
3163 
3164  supervisor_node_get_number_of_contact_points_client.shutdown();
3166 
3167  ros::ServiceClient supervisor_node_get_contact_point_client;
3168  webots_ros::node_get_contact_point supervisor_node_get_contact_point_srv;
3169  supervisor_node_get_contact_point_client =
3170  n.serviceClient<webots_ros::node_get_contact_point>(model_name + "/supervisor/node/get_contact_point");
3171 
3172  supervisor_node_get_contact_point_srv.request.node = from_def_node;
3173  supervisor_node_get_contact_point_srv.request.index = 0;
3174  supervisor_node_get_contact_point_client.call(supervisor_node_get_contact_point_srv);
3175  ROS_INFO("First contact point is at x = %f, y = %f z = %f.", supervisor_node_get_contact_point_srv.response.point.x,
3176  supervisor_node_get_contact_point_srv.response.point.y, supervisor_node_get_contact_point_srv.response.point.z);
3177 
3178  supervisor_node_get_contact_point_client.shutdown();
3180 
3181  ros::ServiceClient supervisor_node_get_contact_point_node_client;
3182  webots_ros::node_get_contact_point_node supervisor_node_get_contact_point_node_srv;
3183  supervisor_node_get_contact_point_node_client =
3184  n.serviceClient<webots_ros::node_get_contact_point_node>(model_name + "/supervisor/node/get_contact_point_node");
3185 
3186  supervisor_node_get_contact_point_node_srv.request.node = from_def_node;
3187  supervisor_node_get_contact_point_node_srv.request.index = 0;
3188  supervisor_node_get_contact_point_node_client.call(supervisor_node_get_contact_point_node_srv);
3189  ROS_INFO("First contact point belong to node '%lu'", supervisor_node_get_contact_point_node_srv.response.node);
3190 
3191  supervisor_node_get_contact_point_node_client.shutdown();
3193 
3194  // wb_supervisor_node_enable_contact_points_tracking
3195  ros::ServiceClient supervisor_node_enable_contact_points_tracking_client;
3196  webots_ros::node_enable_contact_points_tracking supervisor_node_enable_contact_points_tracking_srv;
3197  supervisor_node_enable_contact_points_tracking_client = n.serviceClient<webots_ros::node_enable_contact_points_tracking>(
3198  model_name + "/supervisor/node/enable_contact_points_tracking");
3199 
3200  supervisor_node_enable_contact_points_tracking_srv.request.node = from_def_node;
3201  supervisor_node_enable_contact_points_tracking_srv.request.include_descendants = false;
3202  supervisor_node_enable_contact_points_tracking_client.call(supervisor_node_enable_contact_points_tracking_srv);
3203  ROS_INFO("Contact point tracking success = %d", supervisor_node_enable_contact_points_tracking_srv.response.success);
3204 
3205  supervisor_node_enable_contact_points_tracking_client.shutdown();
3207 
3208  // wb_supervisor_node_disable_contact_points_tracking
3209  ros::ServiceClient supervisor_node_disable_contact_points_tracking_client;
3210  webots_ros::node_disable_contact_points_tracking supervisor_node_disable_contact_points_tracking_srv;
3211  supervisor_node_disable_contact_points_tracking_client = n.serviceClient<webots_ros::node_disable_contact_points_tracking>(
3212  model_name + "/supervisor/node/disable_contact_points_tracking");
3213 
3214  supervisor_node_disable_contact_points_tracking_srv.request.node = from_def_node;
3215  supervisor_node_disable_contact_points_tracking_srv.request.include_descendants = false;
3216  supervisor_node_disable_contact_points_tracking_client.call(supervisor_node_disable_contact_points_tracking_srv);
3217  ROS_INFO("Contact point tracking success = %d", supervisor_node_disable_contact_points_tracking_srv.response.success);
3218 
3219  supervisor_node_disable_contact_points_tracking_client.shutdown();
3221 
3222  // wb_supervisor_node_get_contact_points
3223  ros::ServiceClient supervisor_node_get_contact_points_client;
3224  webots_ros::node_get_contact_points supervisor_node_get_contact_points_srv;
3225  supervisor_node_get_contact_points_client =
3226  n.serviceClient<webots_ros::node_get_contact_points>(model_name + "/supervisor/node/get_contact_points");
3227 
3228  supervisor_node_get_contact_points_srv.request.node = from_def_node;
3229  supervisor_node_get_contact_points_srv.request.include_descendants = false;
3230  supervisor_node_get_contact_points_client.call(supervisor_node_get_contact_points_srv);
3231  ROS_INFO("From_def node got %lu contact points.", supervisor_node_get_contact_points_srv.response.contact_points.size());
3232 
3233  supervisor_node_get_contact_points_client.shutdown();
3235 
3236  // test get_static_balance
3237  // if the node isn't a top Solid webots will throw a warning but still return true to ros
3238  ros::ServiceClient supervisor_node_get_static_balance_client;
3239  webots_ros::node_get_static_balance supervisor_node_get_static_balance_srv;
3240  supervisor_node_get_static_balance_client =
3241  n.serviceClient<webots_ros::node_get_static_balance>(model_name + "/supervisor/node/get_static_balance");
3242 
3243  supervisor_node_get_static_balance_srv.request.node = from_def_node;
3244  supervisor_node_get_static_balance_client.call(supervisor_node_get_static_balance_srv);
3245  ROS_INFO("From_def node balance is %d.", supervisor_node_get_static_balance_srv.response.balance);
3246 
3247  supervisor_node_get_static_balance_client.shutdown();
3249 
3250  // test reset_physics
3251  // if the node isn't a top Solid webots will throw a warning but still return true to ros
3252  ros::ServiceClient supervisor_node_reset_physics_client =
3253  n.serviceClient<webots_ros::node_reset_functions>(model_name + "/supervisor/node/reset_physics");
3254  webots_ros::node_reset_functions supervisor_node_reset_physics_srv;
3255 
3256  supervisor_node_reset_physics_srv.request.node = from_def_node;
3257  if (supervisor_node_reset_physics_client.call(supervisor_node_reset_physics_srv) &&
3258  supervisor_node_reset_physics_srv.response.success == 1)
3259  ROS_INFO("Node physics has been reset successfully.");
3260  else
3261  ROS_ERROR("Failed to call service node_reset_physics.");
3262 
3263  supervisor_node_reset_physics_client.shutdown();
3265 
3266  // test node_save_state
3267  ros::ServiceClient supervisor_node_save_state_client =
3268  n.serviceClient<webots_ros::node_set_string>(model_name + "/supervisor/node/save_state");
3269  webots_ros::node_set_string supervisor_node_save_state_srv;
3270 
3271  supervisor_node_save_state_srv.request.node = from_def_node;
3272  supervisor_node_save_state_srv.request.state_name = "dummy_state";
3273  if (supervisor_node_save_state_client.call(supervisor_node_save_state_srv) &&
3274  supervisor_node_save_state_srv.response.success == 1)
3275  ROS_INFO("Node state has been saved successfully.");
3276  else
3277  ROS_ERROR("Failed to call service node_save_state.");
3278 
3279  supervisor_node_save_state_client.shutdown();
3281 
3282  // test node_load_state
3283  ros::ServiceClient supervisor_node_load_state_client =
3284  n.serviceClient<webots_ros::node_set_string>(model_name + "/supervisor/node/load_state");
3285  webots_ros::node_set_string supervisor_node_load_state_srv;
3286 
3287  supervisor_node_load_state_srv.request.node = from_def_node;
3288  supervisor_node_load_state_srv.request.state_name = "dummy_state";
3289  if (supervisor_node_load_state_client.call(supervisor_node_load_state_srv) &&
3290  supervisor_node_load_state_srv.response.success == 1)
3291  ROS_INFO("Node state has been loaded successfully.");
3292  else
3293  ROS_ERROR("Failed to call service node_load_state.");
3294 
3295  supervisor_node_load_state_client.shutdown();
3297 
3298  // test restart_controller
3299  ros::ServiceClient supervisor_node_restart_controller_client =
3300  n.serviceClient<webots_ros::node_reset_functions>(model_name + "/supervisor/node/restart_controller");
3301  webots_ros::node_reset_functions supervisor_node_restart_controller_srv;
3302 
3303  supervisor_node_restart_controller_srv.request.node = from_def_node;
3304  if (supervisor_node_restart_controller_client.call(supervisor_node_restart_controller_srv) &&
3305  supervisor_node_restart_controller_srv.response.success == 1)
3306  ROS_INFO("Robot controller has been restarted successfully.");
3307  else
3308  ROS_ERROR("Failed to call service node_restart_controller.");
3309 
3310  supervisor_node_restart_controller_client.shutdown();
3312 
3313  ros::ServiceClient supervisor_node_get_field_client;
3314  webots_ros::node_get_field supervisor_node_get_field_srv;
3315  supervisor_node_get_field_client = n.serviceClient<webots_ros::node_get_field>(model_name + "/supervisor/node/get_field");
3316 
3317  supervisor_node_get_field_srv.request.node = root_node;
3318  supervisor_node_get_field_srv.request.fieldName = "children";
3319  supervisor_node_get_field_srv.request.proto = 0;
3320  supervisor_node_get_field_client.call(supervisor_node_get_field_srv);
3321  uint64_t field = supervisor_node_get_field_srv.response.field;
3322 
3323  supervisor_node_get_field_client.shutdown();
3325 
3326  ros::ServiceClient wb_supervisor_node_get_number_of_fields_client;
3327  webots_ros::node_get_number_of_fields wb_supervisor_node_get_number_of_fields_srv;
3328  wb_supervisor_node_get_number_of_fields_client =
3329  n.serviceClient<webots_ros::node_get_number_of_fields>(model_name + "/supervisor/node/get_field_by_index");
3330  wb_supervisor_node_get_number_of_fields_srv.request.node = root_node;
3331  wb_supervisor_node_get_number_of_fields_srv.request.proto = 0;
3332  wb_supervisor_node_get_number_of_fields_client.call(wb_supervisor_node_get_number_of_fields_srv);
3333  ROS_INFO("World's root Group node have %d fields.", wb_supervisor_node_get_number_of_fields_srv.response.value);
3334  wb_supervisor_node_get_number_of_fields_client.shutdown();
3336 
3337  ros::ServiceClient wb_supervisor_node_get_field_by_index_client;
3338  webots_ros::node_get_field_by_index wb_supervisor_node_get_field_by_index_srv;
3339  wb_supervisor_node_get_field_by_index_client =
3340  n.serviceClient<webots_ros::node_get_field_by_index>(model_name + "/supervisor/node/get_field_by_index");
3341  wb_supervisor_node_get_field_by_index_srv.request.node = root_node;
3342  wb_supervisor_node_get_field_by_index_srv.request.index = 0;
3343  wb_supervisor_node_get_field_by_index_client.call(wb_supervisor_node_get_field_by_index_srv);
3344  ROS_INFO("World's root Group node has a single 'children' field: %d.",
3345  wb_supervisor_node_get_field_by_index_srv.response.field == field);
3346  wb_supervisor_node_get_field_by_index_client.shutdown();
3348 
3349  ros::ServiceClient supervisor_field_get_name_client;
3350  webots_ros::field_get_name supervisor_field_get_name_srv;
3351  supervisor_field_get_name_client = n.serviceClient<webots_ros::field_get_name>(model_name + "/supervisor/field/get_name");
3352  supervisor_field_get_name_srv.request.field = field;
3353  supervisor_field_get_name_client.call(supervisor_field_get_name_srv);
3354  ROS_INFO("World's children field has name '%s'.", supervisor_field_get_name_srv.response.name.c_str());
3355  supervisor_field_get_name_client.shutdown();
3357 
3358  ros::ServiceClient supervisor_field_get_type_client;
3359  webots_ros::field_get_type supervisor_field_get_type_srv;
3360  supervisor_field_get_type_client = n.serviceClient<webots_ros::field_get_type>(model_name + "/supervisor/field/get_type");
3361 
3362  supervisor_field_get_type_srv.request.field = field;
3363  supervisor_field_get_type_client.call(supervisor_field_get_type_srv);
3364  ROS_INFO("World's children field is of type %d.", supervisor_field_get_type_srv.response.type);
3365 
3366  supervisor_field_get_type_client.shutdown();
3368 
3369  ros::ServiceClient supervisor_field_get_type_name_client;
3370  webots_ros::field_get_name supervisor_field_get_type_name_srv;
3371  supervisor_field_get_type_name_client =
3372  n.serviceClient<webots_ros::field_get_name>(model_name + "/supervisor/field/get_type_name");
3373 
3374  supervisor_field_get_type_name_srv.request.field = field;
3375  supervisor_field_get_type_name_client.call(supervisor_field_get_type_name_srv);
3376  ROS_INFO("Also known as %s.", supervisor_field_get_type_name_srv.response.name.c_str());
3377 
3378  supervisor_field_get_type_name_client.shutdown();
3380 
3381  ros::ServiceClient supervisor_field_get_count_client;
3382  webots_ros::field_get_count supervisor_field_get_count_srv;
3383  supervisor_field_get_count_client = n.serviceClient<webots_ros::field_get_count>(model_name + "/supervisor/field/get_count");
3384 
3385  supervisor_field_get_count_srv.request.field = field;
3386  supervisor_field_get_count_client.call(supervisor_field_get_count_srv);
3387  if (supervisor_field_get_count_srv.response.count != -1)
3388  ROS_INFO("There is %d nodes in this field.", supervisor_field_get_count_srv.response.count);
3389  else
3390  ROS_ERROR("Illegal call to Field::getCount() argument must be multiple fields.");
3391 
3392  supervisor_field_get_count_client.shutdown();
3394 
3395  supervisor_node_get_field_srv.request.node = from_def_node;
3396  supervisor_node_get_field_srv.request.fieldName = "name";
3397  supervisor_node_get_field_client.call(supervisor_node_get_field_srv);
3398  field = supervisor_node_get_field_srv.response.field;
3399 
3400  ros::ServiceClient supervisor_field_set_string_client;
3401  webots_ros::field_set_string supervisor_field_set_string_srv;
3402  supervisor_field_set_string_client =
3403  n.serviceClient<webots_ros::field_set_string>(model_name + "/supervisor/field/set_string");
3404 
3405  supervisor_field_set_string_srv.request.field = field;
3406  supervisor_field_set_string_srv.request.value = "solid_test";
3407  if (supervisor_field_set_string_client.call(supervisor_field_set_string_srv) &&
3408  supervisor_field_set_string_srv.response.success == 1)
3409  ROS_INFO("Field's string updated to: 'solid_test'.");
3410  else
3411  ROS_ERROR("Failed to call service field_set_string.");
3412 
3413  supervisor_field_set_string_client.shutdown();
3415 
3416  // supervisor_field_enable_sf_tracking
3417  ros::ServiceClient supervisor_field_enable_sf_tracking_client;
3418  webots_ros::field_enable_sf_tracking supervisor_field_enable_sf_tracking_srv;
3419  supervisor_field_enable_sf_tracking_client =
3420  n.serviceClient<webots_ros::field_enable_sf_tracking>(model_name + "/supervisor/field/enable_sf_tracking");
3421 
3422  supervisor_field_enable_sf_tracking_srv.request.field = field;
3423  supervisor_field_enable_sf_tracking_srv.request.sampling_period = 32;
3424  if (supervisor_field_enable_sf_tracking_client.call(supervisor_field_enable_sf_tracking_srv) &&
3425  supervisor_field_enable_sf_tracking_srv.response.success == 1)
3426  ROS_INFO("Field is successfully tracked.");
3427  else
3428  ROS_ERROR("Failed to call service field_enable_sf_tracking.");
3429 
3430  supervisor_field_enable_sf_tracking_client.shutdown();
3432 
3433  // supervisor_field_disable_sf_tracking
3434  ros::ServiceClient supervisor_field_disable_sf_tracking_client;
3435  webots_ros::field_disable_sf_tracking supervisor_field_disable_sf_tracking_srv;
3436  supervisor_field_disable_sf_tracking_client =
3437  n.serviceClient<webots_ros::field_disable_sf_tracking>(model_name + "/supervisor/field/disable_sf_tracking");
3438 
3439  supervisor_field_disable_sf_tracking_srv.request.field = field;
3440  if (supervisor_field_disable_sf_tracking_client.call(supervisor_field_disable_sf_tracking_srv) &&
3441  supervisor_field_disable_sf_tracking_srv.response.success == 1)
3442  ROS_INFO("Field is successfully tracked.");
3443  else
3444  ROS_ERROR("Failed to call service field_disable_sf_tracking.");
3445 
3446  supervisor_field_disable_sf_tracking_client.shutdown();
3448 
3449  // supervisor_field_get_string_client
3450  ros::ServiceClient supervisor_field_get_string_client;
3451  webots_ros::field_get_string supervisor_field_get_string_srv;
3452  supervisor_field_get_string_client =
3453  n.serviceClient<webots_ros::field_get_string>(model_name + "/supervisor/field/get_string");
3454 
3455  supervisor_field_get_string_srv.request.field = field;
3456  supervisor_field_get_string_client.call(supervisor_field_get_string_srv);
3457  ROS_INFO("Field contains \"%s\".", supervisor_field_get_string_srv.response.value.c_str());
3458 
3459  supervisor_field_get_string_client.shutdown();
3461 
3462  supervisor_node_get_field_srv.request.node = root_node;
3463  supervisor_node_get_field_srv.request.fieldName = "children";
3464  supervisor_node_get_field_client.call(supervisor_node_get_field_srv);
3465  field = supervisor_node_get_field_srv.response.field;
3466 
3467  ros::ServiceClient supervisor_field_get_node_client;
3468  webots_ros::field_get_node supervisor_field_get_node_srv;
3469  supervisor_field_get_node_client = n.serviceClient<webots_ros::field_get_node>(model_name + "/supervisor/field/get_node");
3470 
3471  supervisor_field_get_node_srv.request.field = field;
3472  supervisor_field_get_node_srv.request.index = 7;
3473  supervisor_field_get_node_client.call(supervisor_field_get_node_srv);
3474 
3475  supervisor_node_get_type_name_srv.request.node = supervisor_field_get_node_srv.response.node;
3476  supervisor_node_get_type_name_client.call(supervisor_node_get_type_name_srv);
3477  ROS_INFO("Node got from field_get_node is of type %s.", supervisor_node_get_type_name_srv.response.name.c_str());
3478 
3479  // supervisor_node_get_from_def
3480  supervisor_get_from_def_srv.request.name = "CONE";
3481  supervisor_get_from_def_srv.request.proto = 0;
3482  supervisor_get_from_def_client.call(supervisor_get_from_def_srv);
3483  uint64_t cone_node = 0;
3484  if (supervisor_get_from_def_srv.response.node != 0) {
3485  ROS_INFO("Got CONE node from DEF: %lu.", supervisor_get_from_def_srv.response.node);
3486  cone_node = supervisor_get_from_def_srv.response.node;
3487  } else
3488  ROS_ERROR("could not get CONE node from DEF.");
3489 
3490  supervisor_get_from_def_srv.request.name = "HINGE_JOINT";
3491  supervisor_get_from_def_srv.request.proto = 0;
3492  supervisor_get_from_def_client.call(supervisor_get_from_def_srv);
3493  uint64_t hinge_joint_node = 0;
3494  if (supervisor_get_from_def_srv.response.node != 0) {
3495  ROS_INFO("Got HINGE_JOINT node from DEF: %lu.", supervisor_get_from_def_srv.response.node);
3496  hinge_joint_node = supervisor_get_from_def_srv.response.node;
3497  } else
3498  ROS_ERROR("could not get HINGE_JOINT node from DEF.");
3499 
3500  supervisor_node_get_type_name_client.shutdown();
3501  supervisor_get_from_def_client.shutdown();
3502  supervisor_field_get_node_client.shutdown();
3504 
3505  ros::ServiceClient node_get_id_client;
3506  webots_ros::node_get_id node_get_id_srv;
3507  node_get_id_client = n.serviceClient<webots_ros::node_get_id>(model_name + "/supervisor/node/get_id");
3508  node_get_id_srv.request.node = cone_node;
3509  node_get_id_client.call(node_get_id_srv);
3510  int cone_node_id = node_get_id_srv.response.id;
3511  if (cone_node_id > 0)
3512  ROS_INFO("Node id got successfully.");
3513  else
3514  ROS_ERROR("Failed to call service node_get_id.");
3515 
3516  node_get_id_client.shutdown();
3518 
3519  // supervisor_get_from_id
3520  webots_ros::supervisor_get_from_id supervisor_get_from_id_srv;
3521  node_get_id_client = n.serviceClient<webots_ros::supervisor_get_from_id>(model_name + "/supervisor/get_from_id");
3522  supervisor_get_from_id_srv.request.id = cone_node_id;
3523  node_get_id_client.call(supervisor_get_from_id_srv);
3524  uint64_t cone_node_copy = supervisor_get_from_id_srv.response.node;
3525  if (cone_node_copy == cone_node)
3526  ROS_INFO("Cone node got successfully from id.");
3527  else
3528  ROS_ERROR("Failed to call service supervisor_get_from_id.");
3529 
3530  node_get_id_client.shutdown();
3532 
3533  // supervisor_get_from_device
3534  ros::ServiceClient supervisor_get_from_device_client;
3535  webots_ros::supervisor_get_from_string supervisor_get_from_device_srv;
3536  supervisor_get_from_device_client =
3537  n.serviceClient<webots_ros::supervisor_get_from_string>(model_name + "/supervisor/get_from_device");
3538  supervisor_get_from_device_srv.request.value = "compass";
3539  supervisor_get_from_device_client.call(supervisor_get_from_device_srv);
3540  uint64_t compass_node_from_device = supervisor_get_from_device_srv.response.node;
3541  if (compass_node_from_device == from_def_node)
3542  ROS_INFO("Compass node got successfully from tag.");
3543  else
3544  ROS_ERROR("Failed to call service supervisor_get_from_device.");
3545 
3546  supervisor_get_from_device_client.shutdown();
3548 
3549  // node_set_velocity
3550  ros::ServiceClient node_velocity_client;
3551  webots_ros::node_set_velocity node_set_velocity_srv;
3552  node_velocity_client = n.serviceClient<webots_ros::node_set_velocity>(model_name + "/supervisor/node/set_velocity");
3553  node_set_velocity_srv.request.node = cone_node;
3554  node_set_velocity_srv.request.velocity.linear.x = 0.0;
3555  node_set_velocity_srv.request.velocity.linear.y = 0.0;
3556  node_set_velocity_srv.request.velocity.linear.z = 1.0;
3557  node_set_velocity_srv.request.velocity.angular.x = 0.0;
3558  node_set_velocity_srv.request.velocity.angular.y = 0.0;
3559  node_set_velocity_srv.request.velocity.angular.z = 0.0;
3560  if (node_velocity_client.call(node_set_velocity_srv) && node_set_velocity_srv.response.success == 1)
3561  ROS_INFO("Node velocity set successfully.");
3562  else
3563  ROS_ERROR("Failed to call service node_set_velocity.");
3564 
3565  node_velocity_client.shutdown();
3567 
3568  // node_get_velocity
3569  webots_ros::node_get_velocity node_get_velocity_srv;
3570  node_velocity_client = n.serviceClient<webots_ros::node_get_velocity>(model_name + "/supervisor/node/get_velocity");
3571  node_get_velocity_srv.request.node = cone_node;
3572  node_velocity_client.call(node_get_velocity_srv);
3573  if (node_get_velocity_srv.response.velocity.linear.z > 0.8)
3574  ROS_INFO("Node velocity get successfully.");
3575  else
3576  ROS_ERROR("Failed to call service node_get_velocity.");
3577 
3578  node_velocity_client.shutdown();
3580 
3581  // node_add_force_or_torque
3582  ros::ServiceClient node_add_force_or_torque_client;
3583  webots_ros::node_add_force_or_torque node_add_force_or_torque_srv;
3584  node_add_force_or_torque_client =
3585  n.serviceClient<webots_ros::node_add_force_or_torque>(model_name + "/supervisor/node/add_torque");
3586  node_add_force_or_torque_srv.request.node = cone_node;
3587  node_add_force_or_torque_srv.request.force.x = 0.0;
3588  node_add_force_or_torque_srv.request.force.y = 0.0;
3589  node_add_force_or_torque_srv.request.force.z = 1.0;
3590  node_add_force_or_torque_srv.request.relative = 0;
3591  if (node_add_force_or_torque_client.call(node_add_force_or_torque_srv) && node_add_force_or_torque_srv.response.success == 1)
3592  ROS_INFO("Node force added successfully.");
3593  else
3594  ROS_ERROR("Failed to call service node_add_force_or_torque.");
3595 
3596  node_add_force_or_torque_client.shutdown();
3598 
3599  // node_add_force_with_offset
3600  ros::ServiceClient node_add_force_with_offset_client;
3601  webots_ros::node_add_force_with_offset node_add_force_with_offset_srv;
3602  node_add_force_with_offset_client =
3603  n.serviceClient<webots_ros::node_add_force_with_offset>(model_name + "/supervisor/node/add_force_with_offset");
3604  node_add_force_with_offset_srv.request.node = cone_node;
3605  node_add_force_with_offset_srv.request.force.x = 0.0;
3606  node_add_force_with_offset_srv.request.force.y = 0.0;
3607  node_add_force_with_offset_srv.request.force.z = 1.0;
3608  node_add_force_with_offset_srv.request.offset.x = 0.0;
3609  node_add_force_with_offset_srv.request.offset.y = 0.0;
3610  node_add_force_with_offset_srv.request.offset.z = 1.0;
3611  node_add_force_with_offset_srv.request.relative = 0;
3612  if (node_add_force_with_offset_client.call(node_add_force_with_offset_srv) &&
3613  node_add_force_with_offset_srv.response.success == 1)
3614  ROS_INFO("Node force added successfully.");
3615  else
3616  ROS_ERROR("Failed to call service node_add_force_with_offset.");
3617 
3618  node_add_force_with_offset_client.shutdown();
3620 
3621  // node_get_parent
3622  ros::ServiceClient node_get_parent_node_client;
3623  webots_ros::node_get_parent_node node_get_parent_node_srv;
3624  node_get_parent_node_client =
3625  n.serviceClient<webots_ros::node_get_parent_node>(model_name + "/supervisor/node/get_parent_node");
3626  node_get_parent_node_srv.request.node = cone_node;
3627  node_get_parent_node_client.call(node_get_parent_node_srv);
3628  if (node_get_parent_node_srv.response.node == root_node)
3629  ROS_INFO("Node parent got successfully.");
3630  else
3631  ROS_ERROR("Failed to call service node_get_parent_node.");
3632 
3633  node_get_parent_node_client.shutdown();
3635 
3636  // node_set_joint_position
3637  ros::ServiceClient node_set_joint_position_client;
3638  webots_ros::node_set_joint_position node_set_joint_position_srv;
3639  node_set_joint_position_client =
3640  n.serviceClient<webots_ros::node_set_joint_position>(model_name + "/supervisor/node/set_joint_position");
3641  node_set_joint_position_srv.request.node = hinge_joint_node;
3642  node_set_joint_position_srv.request.position = 0.6;
3643  node_set_joint_position_srv.request.index = 1;
3644  node_set_joint_position_client.call(node_set_joint_position_srv);
3645  if (node_set_joint_position_srv.response.success == 1)
3646  ROS_INFO("Joint position set successfully.");
3647  else
3648  ROS_ERROR("Failed to call service node_set_joint_position.");
3649 
3650  node_set_joint_position_client.shutdown();
3652 
3653  // movie
3654  ros::ServiceClient supervisor_movie_is_ready_client;
3655  webots_ros::node_get_status supervisor_movie_is_ready_srv;
3656  supervisor_movie_is_ready_client = n.serviceClient<webots_ros::node_get_status>(model_name + "/supervisor/movie_is_ready");
3657 
3658  if (supervisor_movie_is_ready_client.call(supervisor_movie_is_ready_srv) &&
3659  supervisor_movie_is_ready_srv.response.status == 1)
3660  ROS_INFO("Ready to record a movie.");
3661  else
3662  ROS_ERROR("Failed to call service supervisor_movie_is_ready.");
3663 
3664  supervisor_movie_is_ready_client.shutdown();
3666 
3667  ros::ServiceClient supervisor_movie_start_client;
3668  webots_ros::supervisor_movie_start_recording supervisor_movie_start_srv;
3669  supervisor_movie_start_client =
3670  n.serviceClient<webots_ros::supervisor_movie_start_recording>(model_name + "/supervisor/movie_start_recording");
3671 
3672  supervisor_movie_start_srv.request.filename = std::string(getenv("HOME")) + std::string("/movie_test.mp4");
3673  supervisor_movie_start_srv.request.width = 480;
3674  supervisor_movie_start_srv.request.height = 360;
3675  supervisor_movie_start_srv.request.codec = 1337;
3676  supervisor_movie_start_srv.request.quality = 100;
3677  supervisor_movie_start_srv.request.acceleration = 1;
3678  supervisor_movie_start_srv.request.caption = false;
3679  if (supervisor_movie_start_client.call(supervisor_movie_start_srv) && supervisor_movie_start_srv.response.success == 1)
3680  ROS_INFO("Movie started successfully.");
3681  else
3682  ROS_ERROR("Failed to call service movie_start_recording.");
3683 
3684  supervisor_movie_start_client.shutdown();
3685  for (int i = 0; i < 25; ++i)
3687 
3688  ros::ServiceClient supervisor_movie_stop_client;
3689  webots_ros::get_bool supervisor_movie_stop_srv;
3690  supervisor_movie_stop_client = n.serviceClient<webots_ros::get_bool>(model_name + "/supervisor/movie_stop_recording");
3691 
3692  if (supervisor_movie_stop_client.call(supervisor_movie_stop_srv) && supervisor_movie_stop_srv.response.value)
3693  ROS_INFO("Movie stopped successfully.");
3694  else
3695  ROS_ERROR("Failed to call service movie_stop_recording.");
3696 
3697  supervisor_movie_stop_client.shutdown();
3699 
3700  ros::ServiceClient supervisor_movie_failed_client;
3701  webots_ros::node_get_status supervisor_movie_failed_srv;
3702  supervisor_movie_failed_client = n.serviceClient<webots_ros::node_get_status>(model_name + "/supervisor/movie_failed");
3703 
3704  if (supervisor_movie_failed_client.call(supervisor_movie_failed_srv) && supervisor_movie_failed_srv.response.status == 0)
3705  ROS_INFO("Movie recording executing successfully.");
3706  else
3707  ROS_ERROR("Failed movie recording.");
3708 
3709  supervisor_movie_failed_client.shutdown();
3711 
3712  supervisor_set_label_srv.request.label = "";
3713  supervisor_set_label_client.call(supervisor_set_label_srv);
3714 
3715  supervisor_set_label_client.shutdown();
3717 
3718  // field_remove
3719  ros::ServiceClient remove_node_client;
3720  webots_ros::field_remove field_remove_srv;
3721  remove_node_client = n.serviceClient<webots_ros::field_remove>(model_name + "/supervisor/field/remove");
3722  field_remove_srv.request.field = field;
3723  field_remove_srv.request.index = 5;
3724  if (remove_node_client.call(field_remove_srv) && field_remove_srv.response.success == 1)
3725  ROS_INFO("Field node removed successfully.");
3726  else
3727  ROS_ERROR("Failed to call service field_remove.");
3728 
3729  remove_node_client.shutdown();
3731 
3732  // node_remove
3733  webots_ros::node_remove node_remove_srv;
3734  remove_node_client = n.serviceClient<webots_ros::node_remove>(model_name + "/supervisor/node/remove");
3735  node_remove_srv.request.node = cone_node;
3736  remove_node_client.call(node_remove_srv);
3737  int success1 = node_remove_srv.response.success;
3738  if (success1 == 1)
3739  ROS_INFO("Node removed successfully.");
3740  else
3741  ROS_ERROR("Failed to call service node_removed.");
3742 
3743  remove_node_client.shutdown();
3745 
3746  // node_export_string
3747  ros::ServiceClient node_export_string_client;
3748  webots_ros::node_get_string node_export_string_srv;
3749  node_export_string_client = n.serviceClient<webots_ros::node_get_string>(model_name + "/supervisor/node/export_string");
3750  node_export_string_srv.request.node = root_node;
3751  node_export_string_client.call(node_export_string_srv);
3752  std::string export_string_result = node_export_string_srv.response.value;
3753  if (!export_string_result.find("WorldInfo {") != std::string::npos)
3754  ROS_INFO("Node exported successfully.");
3755  else
3756  ROS_ERROR("Failed to call service node_export_string.");
3757 
3758  node_export_string_client.shutdown();
3760 
3761  // html robot window
3762  ros::ServiceClient wwi_send_client;
3763  wwi_send_client = n.serviceClient<webots_ros::set_string>(model_name + "/robot/wwi_send_text");
3764  webots_ros::set_string wwi_send_srv;
3765  wwi_send_srv.request.value = "test wwi functions from complete_test controller.";
3766  if (wwi_send_client.call(wwi_send_srv) && wwi_send_srv.response.success == 1)
3767  ROS_INFO("Text to robot window successfully sent.");
3768  else
3769  ROS_ERROR("Failed to call service robot/wwi_send_text.");
3770 
3771  wwi_send_client.shutdown();
3773 
3774  ros::ServiceClient wwi_receive_client;
3775  wwi_receive_client = n.serviceClient<webots_ros::get_string>(model_name + "/robot/wwi_receive_text");
3776  webots_ros::get_string wwi_receive_srv;
3777  if (wwi_receive_client.call(wwi_receive_srv) &&
3778  wwi_receive_srv.response.value.compare("Answer: test wwi functions from complete_test controller.") == 0)
3779  ROS_INFO("Text from robot window successfully received.");
3780  else
3781  ROS_ERROR("Failed to call service robot/wwi_receive_text.");
3782 
3783  wwi_receive_client.shutdown();
3785 
3786  // virtual reality headset
3787  ros::ServiceClient virtual_reality_headset_client;
3788  webots_ros::get_bool supervisor_virtual_reality_headset_is_used_srv;
3789  virtual_reality_headset_client =
3790  n.serviceClient<webots_ros::get_bool>(model_name + "/supervisor/vitual_reality_headset_is_used");
3791  virtual_reality_headset_client.call(supervisor_virtual_reality_headset_is_used_srv);
3792  bool used = supervisor_virtual_reality_headset_is_used_srv.response.value;
3793  // to test this service we assume no virtual reality headset is connected
3794  if (!used)
3795  ROS_INFO("No virtual reality headset connected.");
3796  else
3797  ROS_ERROR("Virtual reality headset wrongly detected.");
3798 
3799  virtual_reality_headset_client.shutdown();
3801 
3802  // test field_import_node
3803  // 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
3804  // before
3805  // ros::ServiceClient supervisor_field_import_node_client;
3806  // webots_ros::field_import_node supervisor_field_import_node_srv;
3807  // supervisor_field_import_node_client =
3808  // n.serviceClient<webots_ros::field_import_node>(model_name+"/supervisor/field/import_node");
3809  //
3810  // supervisor_field_import_node_srv.request.field = field;
3811  // supervisor_field_import_node_srv.request.position = 6;
3812  // supervisor_field_import_node_srv.request.filename = "cone_test.wbo";
3813  // if (supervisor_field_import_node_client.call(supervisor_field_import_node_srv) &&
3814  // supervisor_field_import_node_srv.response.success == 1)
3815  // ROS_INFO("New cone add in world.");
3816  // else
3817  // ROS_ERROR("Failed to call service field_import_node.");
3818 
3819  // The next 2 tests are commented but works if you want to use them.
3820  // Since they stop simulation we can't use them if we wants to do other tests afterwards
3821 
3822  //~ ros::ServiceClient supervisor_simulation_quit_client;
3823  //~ webots_ros::set_int supervisor_simulation_quit_srv;
3824  //~ supervisor_simulation_quit_client = n.serviceClient<webots_ros::set_int>(model_name+"/supervisor/simulation_quit");
3825  //~
3826  //~ supervisor_simulation_quit_srv.request.value = EXIT_SUCCESS;
3827  //~ if (supervisor_simulation_quit_client.call(supervisor_simulation_quit_srv) &&
3828  //~ supervisor_simulation_quit_srv.response.success)
3829  //~ ROS_INFO("Webots quit successfully.");
3830  //~ else
3831  //~ ROS_ERROR("Failed to call service simulation_quit.");
3832 
3833  //~ ros::ServiceClient supervisor_simulation_revert_client;
3834  //~ webots_ros::get_bool supervisor_simulation_revert_srv;
3835  //~ supervisor_simulation_revert_client = n.serviceClient<webots_ros::get_bool>(model_name+"/supervisor/simulation_revert");
3836  //~
3837  //~ if (supervisor_simulation_revert_client.call(supervisor_simulation_revert_srv) &&
3838  //~ supervisor_simulation_revert_srv.response.value)
3839  //~ ROS_INFO("Simulation has revert successfully.");
3840  //~ else
3841  //~ ROS_ERROR("Failed to call service simulation_revert.");
3842 
3843  // end of tests
3844  time_step_srv.request.value = 0;
3845  if (time_step_client.call(time_step_srv) && time_step_srv.response.success)
3846  ROS_INFO("Robot's time step called to end tests.");
3847  else
3848  ROS_ERROR("Failed to call service time_step to end tests.");
3849 
3851 
3852  ros::shutdown();
3853 
3854  printf("\nTest Completed\n");
3855  return 0;
3856 }
ros::init_options::AnonymousName
AnonymousName
model_list
static vector< string > model_list
Definition: complete_test.cpp:152
motorSensorCallback
void motorSensorCallback(const webots_ros::Float64Stamped::ConstPtr &value)
Definition: complete_test.cpp:325
GPSCallback
void GPSCallback(const geometry_msgs::PointStamped::ConstPtr &values)
Definition: complete_test.cpp:283
receiverCallback
void receiverCallback(const webots_ros::StringStamped::ConstPtr &value)
Definition: complete_test.cpp:355
radarTargetsCallback
void radarTargetsCallback(const webots_ros::RadarTarget::ConstPtr &target)
Definition: complete_test.cpp:214
lidarCallback
void lidarCallback(const sensor_msgs::Image::ConstPtr &image)
Definition: complete_test.cpp:237
connectorCallback
void connectorCallback(const webots_ros::Int8Stamped::ConstPtr &value)
Definition: complete_test.cpp:241
keyboardCallback
void keyboardCallback(const webots_ros::Int32Stamped::ConstPtr &value)
Definition: complete_test.cpp:209
model_count
static int model_count
Definition: complete_test.cpp:151
connectorPresence
static int connectorPresence
Definition: complete_test.cpp:155
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
distance_sensorCallback
void distance_sensorCallback(const sensor_msgs::Range::ConstPtr &value)
Definition: complete_test.cpp:278
imageColor
static vector< unsigned char > imageColor
Definition: complete_test.cpp:153
ros.h
ros_python.message
string message
Definition: ros_python.py:46
value
int value
main
int main(int argc, char **argv)
Definition: complete_test.cpp:369
accelerometerValues
static double accelerometerValues[3]
Definition: complete_test.cpp:156
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
data
data
ros::spinOnce
ROSCPP_DECL void spinOnce()
callbackCalled
static bool callbackCalled
Definition: complete_test.cpp:162
ros::shutdown
ROSCPP_DECL void shutdown()
TIME_STEP
#define TIME_STEP
Definition: complete_test.cpp:147
size
std::size_t size(custom_string const &s)
altimeterCallback
void altimeterCallback(const webots_ros::Float64Stamped::ConstPtr &value)
Definition: complete_test.cpp:258
ros::Subscriber::shutdown
void shutdown()
segmentationCallback
void segmentationCallback(const sensor_msgs::Image::ConstPtr &values)
Definition: complete_test.cpp:193
GPSSpeedCallback
void GPSSpeedCallback(const webots_ros::Float64Stamped::ConstPtr &value)
Definition: complete_test.cpp:293
ros::Subscriber::getNumPublishers
uint32_t getNumPublishers() const
inertialUnitValues
static double inertialUnitValues[4]
Definition: complete_test.cpp:160
gyroCallback
void gyroCallback(const sensor_msgs::Imu::ConstPtr &values)
Definition: complete_test.cpp:298
touchSensorCallback
void touchSensorCallback(const webots_ros::Float64Stamped::ConstPtr &value)
Definition: complete_test.cpp:335
radarTargetsNumberCallback
void radarTargetsNumberCallback(const webots_ros::Int8Stamped::ConstPtr &value)
Definition: complete_test.cpp:221
touchSensorBumperCallback
void touchSensorBumperCallback(const webots_ros::BoolStamped::ConstPtr &value)
Definition: complete_test.cpp:340
ROS_ERROR
#define ROS_ERROR(...)
quit
void quit(int sig)
Definition: complete_test.cpp:361
ros::ServiceClient::shutdown
void shutdown()
ros::ServiceClient
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
lightSensorCallback
void lightSensorCallback(const sensor_msgs::Illuminance::ConstPtr &value)
Definition: complete_test.cpp:320
battery_sensorCallback
void battery_sensorCallback(const webots_ros::Float64Stamped::ConstPtr &value)
Definition: complete_test.cpp:263
rangeFinderCallback
void rangeFinderCallback(const sensor_msgs::Image::ConstPtr &image)
Definition: complete_test.cpp:227
GPSValues
static double GPSValues[3]
Definition: complete_test.cpp:158
time_step_srv
webots_ros::set_int time_step_srv
Definition: complete_test.cpp:165
joystickCallback
void joystickCallback(const webots_ros::Int8Stamped::ConstPtr &value)
Definition: complete_test.cpp:204
values
std::vector< double > values
urdf
std
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
modelNameCallback
void modelNameCallback(const std_msgs::String::ConstPtr &name)
Definition: complete_test.cpp:167
cameraCallback
void cameraCallback(const sensor_msgs::Image::ConstPtr &values)
Definition: complete_test.cpp:174
positionSensorCallback
void positionSensorCallback(const webots_ros::Float64Stamped::ConstPtr &value)
Definition: complete_test.cpp:330
image
std::vector< unsigned char > image
Definition: e_puck_line.cpp:87
imageRangeFinder
static vector< float > imageRangeFinder
Definition: complete_test.cpp:154
touchSensorValues
static double touchSensorValues[3]
Definition: complete_test.cpp:161
accelerometerCallback
void accelerometerCallback(const sensor_msgs::Imu::ConstPtr &values)
Definition: complete_test.cpp:248
inertialUnitCallback
void inertialUnitCallback(const sensor_msgs::Imu::ConstPtr &values)
Definition: complete_test.cpp:308
ROS_INFO
#define ROS_INFO(...)
touchSensor3DCallback
void touchSensor3DCallback(const geometry_msgs::WrenchStamped::ConstPtr &values)
Definition: complete_test.cpp:345
GyroValues
static double GyroValues[3]
Definition: complete_test.cpp:159
time_step_client
ros::ServiceClient time_step_client
Definition: complete_test.cpp:164
compassValues
static double compassValues[3]
Definition: complete_test.cpp:157
ros::NodeHandle
ros::Subscriber
compassCallback
void compassCallback(const sensor_msgs::MagneticField::ConstPtr &values)
Definition: complete_test.cpp:268
name
name
cameraRecognitionCallback
void cameraRecognitionCallback(const webots_ros::RecognitionObjects::ConstPtr &objects)
Definition: complete_test.cpp:184


webots_ros
Author(s): Cyberbotics
autogenerated on Wed Mar 2 2022 01:15:14