15 #include <geometry_msgs/Twist.h> 16 #include <geometry_msgs/WrenchStamped.h> 17 #include <sensor_msgs/Illuminance.h> 18 #include <sensor_msgs/Image.h> 19 #include <sensor_msgs/Imu.h> 20 #include <sensor_msgs/MagneticField.h> 21 #include <sensor_msgs/NavSatFix.h> 22 #include <sensor_msgs/Range.h> 24 #include <std_msgs/Float32MultiArray.h> 25 #include <std_msgs/Float64.h> 26 #include <std_msgs/Float64MultiArray.h> 27 #include <std_msgs/String.h> 28 #include <std_msgs/UInt16.h> 29 #include <std_msgs/UInt8MultiArray.h> 30 #include <webots_ros/BoolStamped.h> 31 #include <webots_ros/Float64Stamped.h> 32 #include <webots_ros/Int32Stamped.h> 33 #include <webots_ros/Int8Stamped.h> 34 #include <webots_ros/RadarTarget.h> 35 #include <webots_ros/RecognitionObject.h> 36 #include <webots_ros/StringStamped.h> 40 #include <webots_ros/get_bool.h> 41 #include <webots_ros/get_float.h> 42 #include <webots_ros/get_int.h> 43 #include <webots_ros/get_string.h> 44 #include <webots_ros/get_uint64.h> 45 #include <webots_ros/set_bool.h> 46 #include <webots_ros/set_float.h> 47 #include <webots_ros/set_float_array.h> 48 #include <webots_ros/set_int.h> 49 #include <webots_ros/set_string.h> 51 #include <webots_ros/camera_get_focus_info.h> 52 #include <webots_ros/camera_get_info.h> 53 #include <webots_ros/camera_get_zoom_info.h> 54 #include <webots_ros/display_draw_line.h> 55 #include <webots_ros/display_draw_oval.h> 56 #include <webots_ros/display_draw_pixel.h> 57 #include <webots_ros/display_draw_polygon.h> 58 #include <webots_ros/display_draw_rectangle.h> 59 #include <webots_ros/display_draw_text.h> 60 #include <webots_ros/display_get_info.h> 61 #include <webots_ros/display_image_copy.h> 62 #include <webots_ros/display_image_delete.h> 63 #include <webots_ros/display_image_load.h> 64 #include <webots_ros/display_image_new.h> 65 #include <webots_ros/display_image_paste.h> 66 #include <webots_ros/display_image_save.h> 67 #include <webots_ros/display_set_font.h> 68 #include <webots_ros/field_get_bool.h> 69 #include <webots_ros/field_get_color.h> 70 #include <webots_ros/field_get_count.h> 71 #include <webots_ros/field_get_float.h> 72 #include <webots_ros/field_get_int32.h> 73 #include <webots_ros/field_get_node.h> 74 #include <webots_ros/field_get_rotation.h> 75 #include <webots_ros/field_get_string.h> 76 #include <webots_ros/field_get_type.h> 77 #include <webots_ros/field_get_type_name.h> 78 #include <webots_ros/field_get_vec2f.h> 79 #include <webots_ros/field_get_vec3f.h> 80 #include <webots_ros/field_import_node.h> 81 #include <webots_ros/field_remove.h> 82 #include <webots_ros/field_set_bool.h> 83 #include <webots_ros/field_set_color.h> 84 #include <webots_ros/field_set_float.h> 85 #include <webots_ros/field_set_int32.h> 86 #include <webots_ros/field_set_rotation.h> 87 #include <webots_ros/field_set_string.h> 88 #include <webots_ros/field_set_vec2f.h> 89 #include <webots_ros/field_set_vec3f.h> 90 #include <webots_ros/lidar_get_frequency_info.h> 91 #include <webots_ros/lidar_get_info.h> 92 #include <webots_ros/motor_set_control_pid.h> 93 #include <webots_ros/node_get_center_of_mass.h> 94 #include <webots_ros/node_get_contact_point.h> 95 #include <webots_ros/node_get_field.h> 96 #include <webots_ros/node_get_id.h> 97 #include <webots_ros/node_get_name.h> 98 #include <webots_ros/node_get_number_of_contact_points.h> 99 #include <webots_ros/node_get_orientation.h> 100 #include <webots_ros/node_get_parent_node.h> 101 #include <webots_ros/node_get_position.h> 102 #include <webots_ros/node_get_static_balance.h> 103 #include <webots_ros/node_get_status.h> 104 #include <webots_ros/node_get_type.h> 105 #include <webots_ros/node_get_velocity.h> 106 #include <webots_ros/node_remove.h> 107 #include <webots_ros/node_reset_functions.h> 108 #include <webots_ros/node_set_velocity.h> 109 #include <webots_ros/node_set_visibility.h> 110 #include <webots_ros/pen_set_ink_color.h> 111 #include <webots_ros/range_finder_get_info.h> 112 #include <webots_ros/receiver_get_emitter_direction.h> 113 #include <webots_ros/robot_get_device_list.h> 114 #include <webots_ros/robot_set_mode.h> 115 #include <webots_ros/robot_wait_for_user_input_event.h> 116 #include <webots_ros/save_image.h> 117 #include <webots_ros/speaker_play_sound.h> 118 #include <webots_ros/speaker_speak.h> 119 #include <webots_ros/supervisor_get_from_def.h> 120 #include <webots_ros/supervisor_get_from_id.h> 121 #include <webots_ros/supervisor_movie_start_recording.h> 122 #include <webots_ros/supervisor_set_label.h> 123 #include <webots_ros/supervisor_virtual_reality_headset_get_orientation.h> 124 #include <webots_ros/supervisor_virtual_reality_headset_get_position.h> 153 imageColor.resize(values->step * values->height);
154 for (std::vector<unsigned char>::const_iterator it = values->data.begin(); it != values->data.end(); ++it) {
161 ROS_INFO(
"Joystick button pressed: %d (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
165 ROS_INFO(
"Keyboard key pressed: %d (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
169 ROS_INFO(
"Received a radar target with distance=%lf received power=%lf speed=%lf azimuth=%lf (time: %d:%d).",
170 target->distance, target->receivedPower, target->speed, target->azimuth, target->header.stamp.sec,
171 target->header.stamp.nsec);
175 ROS_INFO(
"Number of target seen by the radar: %d (time: %d:%d).", value->data, value->header.stamp.sec,
176 value->header.stamp.nsec);
180 int size = image->width * image->height;
183 const float *depth_data =
reinterpret_cast<const float *
>(&image->data[0]);
184 for (
int i = 0; i < size; ++i)
207 ROS_INFO(
"Battery level is %f (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
216 values->header.stamp.sec, values->header.stamp.nsec);
220 ROS_INFO(
"Distance from object is %f (time: %d:%d).", value->range, value->header.stamp.sec, value->header.stamp.nsec);
223 void GPSCallback(
const sensor_msgs::NavSatFix::ConstPtr &values) {
229 values->header.stamp.nsec);
233 ROS_INFO(
"GPS speed is: %fkm/h (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
242 values->header.stamp.sec, values->header.stamp.nsec);
253 values->header.stamp.nsec);
257 ROS_INFO(
"Light intensity is %f.", value->illuminance);
261 ROS_INFO(
"Motor sensor sent value %f.", value->data);
265 ROS_INFO(
"Position sensor sent value %f (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
269 ROS_INFO(
"Touch sensor sent value %f (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
273 ROS_INFO(
"Touch sensor sent value %d (time: %d:%d).", value->data, value->header.stamp.sec, value->header.stamp.nsec);
286 char *message =
const_cast<char *
>(value->data.c_str());
287 ROS_INFO(
"Received a message %s.", message);
293 ROS_INFO(
"User stopped the 'complete_test' node.");
298 int main(
int argc,
char **argv) {
299 string model_name =
"my_robot";
304 signal(SIGINT,
quit);
320 string controller_args;
321 string controller_name;
325 vector<string> device_list;
327 time_step_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/robot/time_step");
331 ROS_INFO(
"time_step service works.");
333 ROS_ERROR(
"Failed to call service time_step to update robot's time step.");
336 n.
serviceClient<webots_ros::get_int>(model_name +
"/robot/get_number_of_devices");
337 webots_ros::get_int get_number_of_devices_srv;
339 if (get_number_of_devices_client.
call(get_number_of_devices_srv)) {
340 int number_of_devices = get_number_of_devices_srv.response.value;
341 ROS_INFO(
"%s has %d devices.", model_name.c_str(), number_of_devices);
343 ROS_ERROR(
"Failed to call service get_number_of_devices.");
345 get_number_of_devices_client.
shutdown();
349 n.
serviceClient<webots_ros::robot_get_device_list>(model_name +
"/robot/get_device_list");
350 webots_ros::robot_get_device_list device_list_srv;
352 if (device_list_client.
call(device_list_srv)) {
353 device_list = device_list_srv.response.list;
354 for (
unsigned int i = 0; i < device_list.size(); i++)
355 ROS_INFO(
"Device [%d]: %s.", i, device_list[i].c_str());
357 ROS_ERROR(
"Failed to call service device_list.");
363 n.
serviceClient<webots_ros::get_float>(model_name +
"/robot/get_basic_time_step");
364 webots_ros::get_float get_basic_time_step_srv;
366 if (get_basic_time_step_client.
call(get_basic_time_step_srv)) {
367 double basic_time_step = get_basic_time_step_srv.response.value;
368 ROS_INFO(
"%s has a basic time step of %f.", model_name.c_str(), basic_time_step);
370 ROS_ERROR(
"Failed to call service get_basic_time_step.");
372 get_basic_time_step_client.
shutdown();
376 n.
serviceClient<webots_ros::get_string>(model_name +
"/robot/get_controller_arguments");
377 webots_ros::get_string get_controller_arguments_srv;
379 if (get_controller_arguments_client.
call(get_controller_arguments_srv)) {
380 controller_args = get_controller_arguments_srv.response.value;
381 ROS_INFO(
"Controller arguments of %s are %s.", model_name.c_str(), controller_args.c_str());
383 ROS_ERROR(
"Failed to call service get_controller_arguments.");
385 get_controller_arguments_client.
shutdown();
389 n.
serviceClient<webots_ros::get_string>(model_name +
"/robot/get_controller_name");
390 webots_ros::get_string get_controller_name_srv;
392 if (get_controller_name_client.
call(get_controller_name_srv)) {
393 controller_name = get_controller_name_srv.response.value;
394 ROS_INFO(
"Controller name of %s is %s.", model_name.c_str(), controller_name.c_str());
396 ROS_ERROR(
"Failed to call service get_controller_name.");
398 get_controller_name_client.
shutdown();
402 n.
serviceClient<webots_ros::get_string>(model_name +
"/robot/get_custom_data");
403 webots_ros::get_string robot_get_custom_data_srv;
405 if (robot_get_custom_data_client.
call(robot_get_custom_data_srv)) {
406 data = robot_get_custom_data_srv.response.value;
407 ROS_INFO(
"Data of %s is %s.", model_name.c_str(), data.c_str());
409 ROS_ERROR(
"Failed to call service robot_get_custom_data.");
411 robot_get_custom_data_client.
shutdown();
415 webots_ros::get_int get_mode_srv;
417 if (get_mode_client.
call(get_mode_srv)) {
418 mode = get_mode_srv.response.value;
419 ROS_INFO(
"Mode of %s is %d.", model_name.c_str(), mode);
421 ROS_ERROR(
"Failed to call service get_mode.");
427 webots_ros::get_string get_model_srv;
429 if (get_model_client.
call(get_model_srv)) {
430 model = get_model_srv.response.value;
431 ROS_INFO(
"Model of %s is %s.", model_name.c_str(), model.c_str());
433 ROS_ERROR(
"Failed to call service get_model.");
439 webots_ros::get_string get_project_path_srv;
441 if (get_project_path_client.
call(get_project_path_srv)) {
442 path = get_project_path_srv.response.value;
443 ROS_INFO(
"World path of %s is %s.", model_name.c_str(), path.c_str());
445 ROS_ERROR(
"Failed to call service get_project_path.");
452 webots_ros::get_string get_world_path_srv;
454 if (get_world_path_client.
call(get_world_path_srv)) {
455 path = get_world_path_srv.response.value;
456 ROS_INFO(
"Project path of %s is %s.", model_name.c_str(), path.c_str());
458 ROS_ERROR(
"Failed to call service get_project_path.");
464 webots_ros::get_bool get_supervisor_srv;
466 if (get_supervisor_client.
call(get_supervisor_srv)) {
467 if (get_supervisor_srv.response.value)
468 ROS_INFO(
"%s is a supervisor.", model_name.c_str());
470 ROS_ERROR(
"%s isn't a supervisor.", model_name.c_str());
472 ROS_ERROR(
"Failed to call service get_synchronization.");
478 n.
serviceClient<webots_ros::get_bool>(model_name +
"/robot/get_synchronization");
479 webots_ros::get_bool get_synchronization_srv;
481 if (get_synchronization_client.
call(get_synchronization_srv)) {
482 bool synchronization = get_synchronization_srv.response.value;
484 ROS_INFO(
"%s is sync.", model_name.c_str());
486 ROS_INFO(
"%s isn't sync.", model_name.c_str());
488 ROS_ERROR(
"Failed to call service get_synchronization.");
490 get_synchronization_client.
shutdown();
494 webots_ros::get_float get_time_srv;
496 if (get_time_client.
call(get_time_srv)) {
497 double time = get_time_srv.response.value;
498 ROS_INFO(
"Time for %s is %f.", model_name.c_str(), time);
500 ROS_ERROR(
"Failed to call service get_time.");
506 webots_ros::get_int get_type_srv;
508 if (get_type_client.
call(get_type_srv)) {
509 int type = get_type_srv.response.value;
510 ROS_INFO(
"Type of %s is %d.", model_name.c_str(), type);
512 ROS_ERROR(
"Failed to call service get_type.");
518 n.
serviceClient<webots_ros::set_string>(model_name +
"/robot/set_custom_data");
519 webots_ros::set_string robot_set_custom_data_srv;
521 robot_set_custom_data_srv.request.value =
"OVERWRITTEN";
522 if (robot_set_custom_data_client.
call(robot_set_custom_data_srv)) {
523 if (robot_set_custom_data_srv.response.success)
524 ROS_INFO(
"Data of %s has been set to %s.", model_name.c_str(), data.c_str());
526 ROS_ERROR(
"Failed to call service robot_set_custom_data.");
528 robot_set_custom_data_client.
shutdown();
532 webots_ros::robot_set_mode set_mode_srv;
534 set_mode_srv.request.mode = mode;
535 if (set_mode_client.
call(set_mode_srv)) {
536 if (set_mode_srv.response.success == 1)
537 ROS_INFO(
"Mode of %s has been set to %d.", model_name.c_str(), mode);
539 ROS_ERROR(
"Failed to call service set_mode.");
545 webots_ros::set_int enable_keyboard_srv;
548 enable_keyboard_srv.request.value = 32;
549 if (enable_keyboard_client.
call(enable_keyboard_srv) && enable_keyboard_srv.response.success) {
550 ROS_INFO(
"Keyboard of %s has been enabled.", model_name.c_str());
552 ROS_INFO(
"Topics for keyboard initialized.");
554 while (sub_keyboard.getNumPublishers() == 0) {
558 ROS_INFO(
"Topics for keyboard connected.");
560 ROS_ERROR(
"Failed to enable keyboard.");
563 n.
serviceClient<webots_ros::robot_wait_for_user_input_event>(model_name +
"/robot/wait_for_user_input_event");
564 webots_ros::robot_wait_for_user_input_event wait_for_user_input_event_srv;
566 wait_for_user_input_event_srv.request.eventType = 4;
567 wait_for_user_input_event_srv.request.timeout = 20;
568 if (wait_for_user_input_event_client.
call(wait_for_user_input_event_srv))
569 ROS_INFO(
"Detected user input event: %d.", wait_for_user_input_event_srv.response.event);
571 ROS_ERROR(
"Failed to call service wait_for_user_input_event.");
573 wait_for_user_input_event_client.
shutdown();
586 webots_ros::set_float brake_set_srv;
587 brake_set_srv.request.value = 0.55;
588 if (brake_set_client.
call(brake_set_srv) && brake_set_srv.response.success)
589 ROS_INFO(
"Brake damping constant set to 0.55.");
591 ROS_ERROR(
"Failed to call service brake_set_damping_constant.");
598 n.
serviceClient<webots_ros::get_string>(model_name +
"/my_brake/get_motor_name");
599 webots_ros::get_string brake_get_motor_name_srv;
600 if (brake_get_motor_name_client.
call(brake_get_motor_name_srv)) {
601 ROS_INFO(
"Linear motor name returned from Brake API %s.", brake_get_motor_name_srv.response.value.c_str());
602 if (brake_get_motor_name_srv.response.value.compare(
"linear_motor") != 0)
603 ROS_ERROR(
"Failed to call service brake_get_motor_name: received '%s' instead of 'linear_motor'",
604 brake_get_motor_name_srv.response.value.c_str());
606 ROS_ERROR(
"Failed to call service brake_get_motor_name.");
608 brake_get_motor_name_client.
shutdown();
616 double focal_distance = 0.33;
618 webots_ros::set_float camera_set_focal_distance_srv;
619 camera_set_focal_distance_srv.request.value = focal_distance;
620 if (camera_set_client.
call(camera_set_focal_distance_srv) && camera_set_focal_distance_srv.response.success)
621 ROS_INFO(
"Camera focal distance set to %f.", focal_distance);
623 ROS_ERROR(
"Failed to call service camera_set_focal_distance.");
630 camera_set_client = n.
serviceClient<webots_ros::set_float>(model_name +
"/camera/set_fov");
631 webots_ros::set_float camera_set_fov_srv;
632 camera_set_fov_srv.request.value = fov;
633 if (camera_set_client.
call(camera_set_fov_srv) && camera_set_fov_srv.response.success)
634 ROS_INFO(
"Camera fov set to %f.", fov);
636 ROS_ERROR(
"Failed to call service camera_set_fov.");
643 webots_ros::set_int camera_srv;
646 enable_camera_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/camera/enable");
648 if (enable_camera_client.
call(camera_srv) && camera_srv.response.success) {
651 ROS_INFO(
"Topic for camera color initialized.");
656 ROS_INFO(
"Topic for camera color connected.");
658 if (camera_srv.response.success == -1)
659 ROS_ERROR(
"Sampling period is not valid.");
660 ROS_ERROR(
"Failed to enable camera.");
670 webots_ros::camera_get_info get_info_srv;
671 if (get_info_client.
call(get_info_srv))
672 ROS_INFO(
"Camera of %s has a width of %d, a height of %d, a field of view of %f, a near range of %f.", model_name.c_str(),
673 get_info_srv.response.width, get_info_srv.response.height, get_info_srv.response.Fov,
674 get_info_srv.response.nearRange);
676 ROS_ERROR(
"Failed to call service camera_get_info.");
677 if (get_info_srv.response.Fov != fov)
678 ROS_ERROR(
"Failed to set camera fov.");
684 get_info_client = n.
serviceClient<webots_ros::camera_get_focus_info>(model_name +
"/camera/get_focus_info");
685 webots_ros::camera_get_focus_info camera_get_focus_info_srv;
686 if (get_info_client.
call(camera_get_focus_info_srv))
687 ROS_INFO(
"Camera of %s has focalLength %f, focalDistance %f, maxFocalDistance %f, and minFocalDistance %f.",
688 model_name.c_str(), camera_get_focus_info_srv.response.focalLength,
689 camera_get_focus_info_srv.response.focalDistance, camera_get_focus_info_srv.response.maxFocalDistance,
690 camera_get_focus_info_srv.response.minFocalDistance);
692 ROS_ERROR(
"Failed to call service camera_get_focus_info.");
693 if (camera_get_focus_info_srv.response.focalDistance != focal_distance)
694 ROS_ERROR(
"Failed to set camera focal distance.");
700 get_info_client = n.
serviceClient<webots_ros::camera_get_zoom_info>(model_name +
"/camera/get_zoom_info");
701 webots_ros::camera_get_zoom_info camera_get_zoom_info_srv;
702 if (get_info_client.
call(camera_get_zoom_info_srv))
703 ROS_INFO(
"Camera of %s has min fov %f, anf max fov %f.", model_name.c_str(), camera_get_zoom_info_srv.response.minFov,
704 camera_get_zoom_info_srv.response.maxFov);
706 ROS_ERROR(
"Failed to call service camera_get_zoom_info.");
712 get_info_client = n.
serviceClient<webots_ros::get_bool>(model_name +
"/camera/has_recognition");
713 webots_ros::get_bool camera_has_recognition_srv;
714 if (get_info_client.
call(camera_has_recognition_srv))
715 if (camera_has_recognition_srv.response.value)
716 ROS_INFO(
"Recognition capability of camera of %s found.", model_name.c_str());
718 ROS_ERROR(
"Recognition capability of camera of %s not found.", model_name.c_str());
720 ROS_ERROR(
"Failed to call service camera_get_zoom_info.");
727 webots_ros::save_image save_image_srv;
728 save_image_srv.request.filename = std::string(getenv(
"HOME")) + std::string(
"/test_image_camera.png");
729 save_image_srv.request.quality = 100;
731 if (save_image_client.
call(save_image_srv) && save_image_srv.response.success == 1)
734 ROS_ERROR(
"Failed to call service save_image.");
747 webots_ros::get_string device_get_name_srv;
748 if (device_get_name_client.
call(device_get_name_srv))
749 ROS_INFO(
"Camera device name: %s.", device_get_name_srv.response.value.c_str());
751 ROS_ERROR(
"Failed to call service get_name.");
758 webots_ros::get_string device_get_model_srv;
759 if (device_get_model_client.
call(device_get_model_srv))
760 ROS_INFO(
"Camera device model: %s.", device_get_model_srv.response.value.c_str());
762 ROS_ERROR(
"Failed to call service get_model.");
772 webots_ros::set_int accelerometer_srv;
776 set_accelerometer_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/accelerometer/enable");
778 accelerometer_srv.request.value = 64;
779 if (set_accelerometer_client.
call(accelerometer_srv) && accelerometer_srv.response.success) {
786 if (accelerometer_srv.response.success == -1)
787 ROS_ERROR(
"Sampling period is not valid.");
788 ROS_ERROR(
"Failed to enable accelerometer.");
796 webots_ros::get_int sampling_period_accelerometer_srv;
798 sampling_period_accelerometer_client =
799 n.
serviceClient<webots_ros::get_int>(model_name +
"/accelerometer/get_sampling_period");
800 sampling_period_accelerometer_client.
call(sampling_period_accelerometer_srv);
801 ROS_INFO(
"Accelerometer is enabled with a sampling period of %d.", sampling_period_accelerometer_srv.response.value);
803 accelerometer_srv.request.value = 32;
804 if (set_accelerometer_client.
call(accelerometer_srv) && accelerometer_srv.response.success) {
811 if (accelerometer_srv.response.success == -1)
812 ROS_ERROR(
"Sampling period is not valid.");
813 ROS_ERROR(
"Failed to enable accelerometer.");
818 set_accelerometer_client.
shutdown();
821 sampling_period_accelerometer_client.
call(sampling_period_accelerometer_srv);
822 ROS_INFO(
"Accelerometer is enabled with a sampling period of %d.", sampling_period_accelerometer_srv.response.value);
829 sampling_period_accelerometer_client.
call(sampling_period_accelerometer_srv);
830 ROS_INFO(
"Accelerometer is disabled (sampling period is %d).", sampling_period_accelerometer_srv.response.value);
832 sampling_period_accelerometer_client.
shutdown();
840 webots_ros::set_int battery_sensor_srv;
842 set_battery_sensor_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/battery_sensor/enable");
845 webots_ros::get_int sampling_period_battery_sensor_srv;
846 sampling_period_battery_sensor_client =
847 n.
serviceClient<webots_ros::get_int>(model_name +
"/battery_sensor/get_sampling_period");
849 battery_sensor_srv.request.value = 32;
850 if (set_battery_sensor_client.
call(battery_sensor_srv) && battery_sensor_srv.response.success) {
851 ROS_INFO(
"Battery_sensor enabled.");
858 if (!battery_sensor_srv.response.success)
859 ROS_ERROR(
"Sampling period is not valid.");
860 ROS_ERROR(
"Failed to enable battery_sensor.");
868 sampling_period_battery_sensor_client.call(sampling_period_battery_sensor_srv);
869 ROS_INFO(
"Battery_sensor is enabled with a sampling period of %d.", sampling_period_battery_sensor_srv.response.value);
877 sampling_period_battery_sensor_client.call(sampling_period_battery_sensor_srv);
878 ROS_INFO(
"Battery_sensor is disabled (sampling period is %d).", sampling_period_battery_sensor_srv.response.value);
880 set_battery_sensor_client.
shutdown();
881 sampling_period_battery_sensor_client.shutdown();
889 webots_ros::set_int compass_srv;
891 set_compass_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/compass/enable");
894 webots_ros::get_int sampling_period_compass_srv;
895 sampling_period_compass_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/compass/get_sampling_period");
897 compass_srv.request.value = 32;
898 if (set_compass_client.
call(compass_srv) && compass_srv.response.success == 1) {
906 if (compass_srv.response.success == -1)
907 ROS_ERROR(
"Sampling period is not valid.");
908 ROS_ERROR(
"Failed to enable compass.");
916 sampling_period_compass_client.call(sampling_period_compass_srv);
917 ROS_INFO(
"Compass is enabled with a sampling period of %d.", sampling_period_compass_srv.response.value);
925 sampling_period_compass_client.call(sampling_period_compass_srv);
926 ROS_INFO(
"Compass is disabled (sampling period is %d).", sampling_period_compass_srv.response.value);
929 sampling_period_compass_client.shutdown();
937 webots_ros::set_int connector_srv;
939 connector_enable_presence_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/connector/presence_sensor/enable");
941 connector_srv.request.value = 32;
942 if (connector_enable_presence_client.
call(connector_srv) && connector_srv.response.success) {
943 ROS_INFO(
"Connector's presence sensor enabled.");
950 if (!connector_srv.response.success)
951 ROS_ERROR(
"Sampling period is not valid.");
952 ROS_ERROR(
"Failed to enable connector's presence sensor.");
962 connector_srv.request.value = 0;
963 if (connector_enable_presence_client.
call(connector_srv) && connector_srv.response.success)
964 ROS_INFO(
"Connector's presence sensor disabled.");
966 if (!connector_srv.response.success)
967 ROS_ERROR(
"Sampling period is not valid.");
968 ROS_ERROR(
"Failed to disable connector's presence sensor.");
973 webots_ros::set_bool connector_lock_srv;
974 connector_lock_client = n.
serviceClient<webots_ros::set_bool>(model_name +
"/connector/lock");
976 connector_lock_srv.request.value =
true;
977 if (connector_lock_client.
call(connector_lock_srv) && connector_lock_srv.response.success)
978 ROS_INFO(
"Connector has been locked.");
980 ROS_INFO(
"Failed to lock connector.");
983 connector_enable_presence_client.
shutdown();
991 webots_ros::display_get_info display_get_info_srv;
992 display_get_info_client = n.
serviceClient<webots_ros::display_get_info>(model_name +
"/display/get_info");
994 display_get_info_client.
call(display_get_info_srv);
995 ROS_INFO(
"Display's width is %d and its height is %d.", display_get_info_srv.response.width,
996 display_get_info_srv.response.height);
1002 webots_ros::set_int display_set_color_srv;
1003 display_set_color_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/display/set_color");
1005 display_set_color_srv.request.value = 0xFF0000;
1006 if (display_set_color_client.
call(display_set_color_srv) && display_set_color_srv.response.success)
1007 ROS_INFO(
"Display's color has been updated.");
1009 ROS_ERROR(
"Failed to call service display_set_color. Success = %d.", display_set_color_srv.response.success);
1011 display_set_color_client.
shutdown();
1015 webots_ros::set_float display_set_alpha_srv;
1016 display_set_alpha_client = n.
serviceClient<webots_ros::set_float>(model_name +
"/display/set_alpha");
1018 display_set_alpha_srv.request.value = 1.0;
1019 if (display_set_alpha_client.
call(display_set_alpha_srv) && display_set_alpha_srv.response.success)
1020 ROS_INFO(
"Display's alpha has been updated.");
1022 ROS_ERROR(
"Failed to call service display_set_alpha.");
1024 display_set_alpha_client.
shutdown();
1028 webots_ros::set_float display_set_opacity_srv;
1029 display_set_opacity_client = n.
serviceClient<webots_ros::set_float>(model_name +
"/display/set_opacity");
1031 display_set_opacity_srv.request.value = 1.0;
1032 if (display_set_opacity_client.
call(display_set_opacity_srv) && display_set_opacity_srv.response.success)
1033 ROS_INFO(
"Display's opacity has been updated.");
1035 ROS_ERROR(
"Failed to call service display_set_opacity.");
1037 display_set_opacity_client.
shutdown();
1041 webots_ros::display_set_font display_set_font_srv;
1042 display_set_font_client = n.
serviceClient<webots_ros::display_set_font>(model_name +
"/display/set_font");
1044 display_set_font_srv.request.font =
"Arial";
1045 display_set_font_srv.request.size = 8;
1046 display_set_font_srv.request.antiAliasing = 0;
1047 if (display_set_font_client.
call(display_set_font_srv) && display_set_font_srv.response.success == 1)
1048 ROS_INFO(
"Display's font has been updated.");
1050 ROS_ERROR(
"Failed to call service display_set_font. Success = %d.", display_set_font_srv.response.success);
1052 display_set_font_client.
shutdown();
1056 webots_ros::display_draw_pixel display_draw_pixel_srv;
1057 display_draw_pixel_client = n.
serviceClient<webots_ros::display_draw_pixel>(model_name +
"/display/draw_pixel");
1059 display_draw_pixel_srv.request.x1 = 10;
1060 display_draw_pixel_srv.request.y1 = 10;
1061 if (display_draw_pixel_client.
call(display_draw_pixel_srv) && display_draw_pixel_srv.response.success == 1)
1062 ROS_INFO(
"Pixel drawn at x =32 and y = 32 on the display.");
1064 ROS_ERROR(
"Failed to call service display_draw_pixel. Success = %d.", display_draw_pixel_srv.response.success);
1066 display_draw_pixel_client.
shutdown();
1070 webots_ros::display_draw_line display_draw_line_srv;
1071 display_draw_line_client = n.
serviceClient<webots_ros::display_draw_line>(model_name +
"/display/draw_line");
1073 display_draw_line_srv.request.x1 = 32;
1074 display_draw_line_srv.request.x2 = 63;
1075 display_draw_line_srv.request.y1 = 32;
1076 display_draw_line_srv.request.y2 = 42;
1077 if (display_draw_line_client.
call(display_draw_line_srv) && display_draw_line_srv.response.success == 1)
1078 ROS_INFO(
"Line drawn at x =32 and y = 32 on the display.");
1080 ROS_ERROR(
"Failed to call service display_draw_line. Success = %d.", display_draw_line_srv.response.success);
1082 display_draw_line_client.
shutdown();
1086 webots_ros::display_draw_rectangle display_draw_rectangle_srv;
1087 display_draw_rectangle_client = n.
serviceClient<webots_ros::display_draw_rectangle>(model_name +
"/display/draw_rectangle");
1089 display_draw_rectangle_srv.request.x = 2;
1090 display_draw_rectangle_srv.request.y = 32;
1091 display_draw_rectangle_srv.request.width = 10;
1092 display_draw_rectangle_srv.request.height = 5;
1093 if (display_draw_rectangle_client.
call(display_draw_rectangle_srv) && display_draw_rectangle_srv.response.success == 1)
1094 ROS_INFO(
"Rectangle drawn at x =32 and y = 32 with width = 10 and height = 5 on the display.");
1096 ROS_ERROR(
"Failed to call service display_draw_rectangle. Success = %d.", display_draw_rectangle_srv.response.success);
1098 display_draw_rectangle_client.
shutdown();
1102 webots_ros::display_draw_oval display_draw_oval_srv;
1103 display_draw_oval_client = n.
serviceClient<webots_ros::display_draw_oval>(model_name +
"/display/draw_oval");
1105 display_draw_oval_srv.request.cx = 32;
1106 display_draw_oval_srv.request.cy = 6;
1107 display_draw_oval_srv.request.a = 10;
1108 display_draw_oval_srv.request.b = 5;
1110 if (display_draw_oval_client.
call(display_draw_oval_srv) && display_draw_oval_srv.response.success == 1)
1111 ROS_INFO(
"Oval drawn at x =32 and y = 6 and axes a = 10 and b = 5 on the display.");
1113 ROS_ERROR(
"Failed to call service display_draw_oval. Success = %d.", display_draw_oval_srv.response.success);
1115 display_draw_oval_client.
shutdown();
1119 webots_ros::display_draw_polygon display_draw_polygon_srv;
1120 display_draw_polygon_client = n.
serviceClient<webots_ros::display_draw_polygon>(model_name +
"/display/draw_polygon");
1122 display_draw_polygon_srv.request.x.push_back(55);
1123 display_draw_polygon_srv.request.y.push_back(55);
1124 display_draw_polygon_srv.request.x.push_back(50);
1125 display_draw_polygon_srv.request.y.push_back(50);
1126 display_draw_polygon_srv.request.x.push_back(45);
1127 display_draw_polygon_srv.request.y.push_back(45);
1128 display_draw_polygon_srv.request.x.push_back(45);
1129 display_draw_polygon_srv.request.y.push_back(55);
1130 display_draw_polygon_srv.request.x.push_back(40);
1131 display_draw_polygon_srv.request.y.push_back(50);
1132 display_draw_polygon_srv.request.size = 5;
1133 if (display_draw_polygon_client.
call(display_draw_polygon_srv) && display_draw_polygon_srv.response.success == 1)
1134 ROS_INFO(
"Polygon drawn on the display.");
1136 ROS_ERROR(
"Failed to call service display_draw_polygon. Success = %d.", display_draw_polygon_srv.response.success);
1138 display_draw_polygon_client.
shutdown();
1142 webots_ros::display_draw_text display_draw_text_srv;
1143 display_draw_text_client = n.
serviceClient<webots_ros::display_draw_text>(model_name +
"/display/draw_text");
1145 display_draw_text_srv.request.x = 10;
1146 display_draw_text_srv.request.y = 52;
1147 display_draw_text_srv.request.text =
"hello world";
1148 if (display_draw_text_client.
call(display_draw_text_srv) && display_draw_text_srv.response.success == 1)
1149 ROS_INFO(
"Hello World written at x =10 and y = 52 on the display.");
1151 ROS_ERROR(
"Failed to call service display_draw_text. Success = %d.", display_draw_text_srv.response.success);
1153 display_draw_text_client.
shutdown();
1157 webots_ros::display_draw_rectangle display_fill_rectangle_srv;
1158 display_fill_rectangle_client = n.
serviceClient<webots_ros::display_draw_rectangle>(model_name +
"/display/fill_rectangle");
1160 display_fill_rectangle_srv.request.x = 2;
1161 display_fill_rectangle_srv.request.y = 32;
1162 display_fill_rectangle_srv.request.width = 10;
1163 display_fill_rectangle_srv.request.height = 5;
1164 if (display_fill_rectangle_client.
call(display_fill_rectangle_srv) && display_fill_rectangle_srv.response.success == 1)
1165 ROS_INFO(
"Rectangle filled at x =32 and y = 32 with width = 10 and height = 5 on the display.");
1167 ROS_ERROR(
"Failed to call service display_fill_rectangle. Success = %d.", display_fill_rectangle_srv.response.success);
1169 display_fill_rectangle_client.
shutdown();
1173 webots_ros::display_draw_oval display_fill_oval_srv;
1174 display_fill_oval_client = n.
serviceClient<webots_ros::display_draw_oval>(model_name +
"/display/fill_oval");
1176 display_fill_oval_srv.request.cx = 32;
1177 display_fill_oval_srv.request.cy = 6;
1178 display_fill_oval_srv.request.a = 10;
1179 display_fill_oval_srv.request.b = 5;
1181 if (display_fill_oval_client.
call(display_fill_oval_srv) && display_fill_oval_srv.response.success == 1)
1182 ROS_INFO(
"Oval filled at x =32 and y = 6 and axes a = 10 and b = 5 on the display.");
1184 ROS_ERROR(
"Failed to call service display_fill_oval. Success = %d.", display_fill_oval_srv.response.success);
1186 display_fill_oval_client.
shutdown();
1190 webots_ros::display_draw_polygon display_fill_polygon_srv;
1191 display_fill_polygon_client = n.
serviceClient<webots_ros::display_draw_polygon>(model_name +
"/display/fill_polygon");
1193 display_fill_polygon_srv.request.x.push_back(55);
1194 display_fill_polygon_srv.request.y.push_back(55);
1195 display_fill_polygon_srv.request.x.push_back(50);
1196 display_fill_polygon_srv.request.y.push_back(50);
1197 display_fill_polygon_srv.request.x.push_back(45);
1198 display_fill_polygon_srv.request.y.push_back(45);
1199 display_fill_polygon_srv.request.x.push_back(45);
1200 display_fill_polygon_srv.request.y.push_back(55);
1201 display_fill_polygon_srv.request.x.push_back(40);
1202 display_fill_polygon_srv.request.y.push_back(50);
1203 display_fill_polygon_srv.request.size = 5;
1204 if (display_fill_polygon_client.
call(display_fill_polygon_srv) && display_fill_polygon_srv.response.success == 1)
1205 ROS_INFO(
"Polygon filled on the display.");
1207 ROS_ERROR(
"Failed to call service display_fill_polygon. Success = %d.", display_fill_polygon_srv.response.success);
1209 display_fill_polygon_client.
shutdown();
1215 webots_ros::display_image_new display_image_new_srv;
1216 display_image_new_client = n.
serviceClient<webots_ros::display_image_new>(model_name +
"/display/image_new");
1218 display_image_new_srv.request.format = 3;
1219 display_image_new_srv.request.width = 10;
1220 display_image_new_srv.request.height = 5;
1221 display_image_new_srv.request.data.push_back(1);
1222 display_image_new_srv.request.data.push_back(2);
1223 display_image_new_srv.request.data.push_back(5);
1224 display_image_new_srv.request.data.push_back(3);
1225 display_image_new_srv.request.data.push_back(4);
1226 display_image_new_client.
call(display_image_new_srv);
1228 uint64_t new_image = display_image_new_srv.response.ir;
1230 display_image_new_client.
shutdown();
1234 webots_ros::display_image_copy display_image_copy_srv;
1235 display_image_copy_client = n.
serviceClient<webots_ros::display_image_copy>(model_name +
"/display/image_copy");
1237 display_image_copy_srv.request.x = 0;
1238 display_image_copy_srv.request.y = 32;
1239 display_image_copy_srv.request.width = 64;
1240 display_image_copy_srv.request.height = 32;
1241 display_image_copy_client.
call(display_image_copy_srv);
1243 uint64_t copy_image = display_image_copy_srv.response.ir;
1245 display_image_copy_client.
shutdown();
1249 webots_ros::display_image_paste display_image_paste_srv;
1250 display_image_paste_client = n.
serviceClient<webots_ros::display_image_paste>(model_name +
"/display/image_paste");
1252 display_image_paste_srv.request.ir = copy_image;
1253 display_image_paste_srv.request.x = 0;
1254 display_image_paste_srv.request.y = 0;
1255 display_image_paste_srv.request.blend = 1;
1256 if (display_image_paste_client.
call(display_image_paste_srv) && display_image_paste_srv.response.success == 1)
1257 ROS_INFO(
"Image successfully copy/paste.");
1259 ROS_ERROR(
"Failed to call service display_image_paste to paste image.");
1261 display_image_paste_client.
shutdown();
1267 webots_ros::display_image_save display_image_save_srv;
1268 display_image_save_client = n.
serviceClient<webots_ros::display_image_save>(model_name +
"/display/image_save");
1270 display_image_save_srv.request.ir = copy_image;
1271 display_image_save_srv.request.filename = std::string(getenv(
"HOME")) + std::string(
"/copy_image.png");
1272 if (display_image_save_client.
call(display_image_save_srv) && display_image_save_srv.response.success == 1)
1273 ROS_INFO(
"Image successfully saved.");
1275 ROS_ERROR(
"Failed to call service display_image_save to save image.");
1277 display_image_save_client.
shutdown();
1281 webots_ros::display_image_load display_image_load_srv;
1282 display_image_load_client = n.
serviceClient<webots_ros::display_image_load>(model_name +
"/display/image_load");
1284 display_image_load_srv.request.filename = std::string(getenv(
"HOME")) + std::string(
"/test_image_camera.png");
1285 display_image_load_client.
call(display_image_load_srv);
1286 ROS_INFO(
"Image successfully loaded to clipboard.");
1287 uint64_t loaded_image = display_image_load_srv.response.ir;
1289 display_image_paste_srv.request.ir = loaded_image;
1290 if (display_image_paste_client.
call(display_image_paste_srv) && display_image_paste_srv.response.success == 1)
1291 ROS_INFO(
"Image successfully load and paste.");
1293 ROS_ERROR(
"Failed to call service display_image_paste to paste image.");
1295 display_image_load_client.
shutdown();
1299 webots_ros::display_image_delete display_image_delete_srv;
1300 display_image_delete_client = n.
serviceClient<webots_ros::display_image_delete>(model_name +
"/display/image_delete");
1302 display_image_delete_srv.request.ir = loaded_image;
1303 if (display_image_delete_client.
call(display_image_delete_srv) && display_image_delete_srv.response.success == 1)
1304 ROS_INFO(
"Loaded image has been deleted.");
1306 ROS_ERROR(
"Failed to call service display_image_delete.");
1308 display_image_delete_srv.request.ir = copy_image;
1309 if (display_image_delete_client.
call(display_image_delete_srv) && display_image_delete_srv.response.success == 1)
1310 ROS_INFO(
"Copy image has been deleted.");
1312 ROS_ERROR(
"Failed to call service display_image_delete.");
1314 display_image_delete_srv.request.ir = new_image;
1315 if (display_image_delete_client.
call(display_image_delete_srv) && display_image_delete_srv.response.success == 1)
1316 ROS_INFO(
"New image has been deleted.");
1318 ROS_ERROR(
"Failed to call service display_image_delete.");
1320 display_image_delete_client.
shutdown();
1328 webots_ros::set_int distance_sensor_srv;
1330 set_distance_sensor_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/distance_sensor/enable");
1333 webots_ros::get_int sampling_period_distance_sensor_srv;
1334 sampling_period_distance_sensor_client =
1335 n.
serviceClient<webots_ros::get_int>(model_name +
"/distance_sensor/get_sampling_period");
1338 webots_ros::get_float min_value_distance_sensor_srv;
1339 min_value_distance_sensor_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/distance_sensor/get_min_value");
1340 if (min_value_distance_sensor_client.call(min_value_distance_sensor_srv))
1341 ROS_INFO(
"Distance_sensor min value = %g.", min_value_distance_sensor_srv.response.value);
1343 ROS_ERROR(
"Failed to get the minimum value of 'distance_sensor'.");
1344 min_value_distance_sensor_client.shutdown();
1347 webots_ros::get_float max_value_distance_sensor_srv;
1348 max_value_distance_sensor_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/distance_sensor/get_max_value");
1349 if (max_value_distance_sensor_client.
call(max_value_distance_sensor_srv))
1350 ROS_INFO(
"Distance_sensor max value = %g.", max_value_distance_sensor_srv.response.value);
1352 ROS_ERROR(
"Failed to get the maximum value of 'distance_sensor'.");
1353 max_value_distance_sensor_client.
shutdown();
1356 webots_ros::get_float aperture_distance_sensor_srv;
1357 aperture_distance_sensor_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/distance_sensor/get_aperture");
1358 if (aperture_distance_sensor_client.
call(aperture_distance_sensor_srv))
1359 ROS_INFO(
"Distance_sensor aperture = %g.", aperture_distance_sensor_srv.response.value);
1361 ROS_ERROR(
"Failed to get the aperture of 'distance_sensor'.");
1362 aperture_distance_sensor_client.
shutdown();
1364 distance_sensor_srv.request.value = 32;
1365 if (set_distance_sensor_client.
call(distance_sensor_srv) && distance_sensor_srv.response.success) {
1366 ROS_INFO(
"Distance_sensor enabled.");
1373 if (!distance_sensor_srv.response.success)
1374 ROS_ERROR(
"Sampling period is not valid.");
1375 ROS_ERROR(
"Failed to enable distance_sensor.");
1383 sampling_period_distance_sensor_client.call(sampling_period_distance_sensor_srv);
1384 ROS_INFO(
"Distance_sensor is enabled with a sampling period of %d.", sampling_period_distance_sensor_srv.response.value);
1392 sampling_period_distance_sensor_client.call(sampling_period_distance_sensor_srv);
1393 ROS_INFO(
"Distance_sensor is disabled (sampling period is %d).", sampling_period_distance_sensor_srv.response.value);
1395 set_distance_sensor_client.
shutdown();
1396 sampling_period_distance_sensor_client.shutdown();
1404 webots_ros::set_string emitter_send_srv;
1405 emitter_send_client = n.
serviceClient<webots_ros::set_string>(model_name +
"/emitter/send");
1407 emitter_send_srv.request.value =
"abc";
1409 if (emitter_send_client.
call(emitter_send_srv) && emitter_send_srv.response.success)
1410 ROS_INFO(
"Emitter has sent data.");
1412 ROS_ERROR(
"Failed to call service emitter_send to send data.");
1418 webots_ros::get_int emitter_get_buffer_size_srv;
1419 emitter_get_buffer_size_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/emitter/get_buffer_size");
1421 emitter_get_buffer_size_client.
call(emitter_get_buffer_size_srv);
1422 ROS_INFO(
"Emitter's buffer is of size %d.", emitter_get_buffer_size_srv.response.value);
1424 emitter_get_buffer_size_client.
shutdown();
1428 webots_ros::set_int emitter_set_channel_srv;
1429 emitter_set_channel_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/emitter/set_channel");
1431 emitter_set_channel_srv.request.value = 1;
1433 if (emitter_set_channel_client.
call(emitter_set_channel_srv) && emitter_set_channel_srv.response.success)
1434 ROS_INFO(
"Emitter has update the channel.");
1436 ROS_ERROR(
"Failed to call service emitter_set_channel to update channel.");
1438 emitter_set_channel_client.
shutdown();
1442 webots_ros::set_float emitter_set_range_srv;
1443 emitter_set_range_client = n.
serviceClient<webots_ros::set_float>(model_name +
"/emitter/set_range");
1445 emitter_set_range_srv.request.value = 50;
1447 if (emitter_set_range_client.
call(emitter_set_range_srv) && emitter_set_range_srv.response.success)
1448 ROS_INFO(
"Emitter has update the range.");
1450 ROS_ERROR(
"Failed to call service emitter_set_range to update range.");
1452 emitter_set_range_client.
shutdown();
1456 webots_ros::get_int emitter_get_channel_srv;
1457 emitter_get_channel_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/emitter/get_channel");
1459 emitter_get_channel_client.
call(emitter_get_channel_srv);
1460 ROS_INFO(
"Emitter uses channel %d.", emitter_get_channel_srv.response.value);
1462 emitter_get_channel_client.
shutdown();
1466 webots_ros::get_float emitter_get_range_srv;
1467 emitter_get_range_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/emitter/get_range");
1469 emitter_get_range_client.
call(emitter_get_range_srv);
1470 ROS_INFO(
"Emitter has a range of %f.", emitter_get_range_srv.response.value);
1472 emitter_get_range_client.
shutdown();
1480 webots_ros::set_int GPS_srv;
1483 set_GPS_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/gps/enable");
1486 webots_ros::get_int sampling_period_GPS_srv;
1487 sampling_period_GPS_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/gps/get_sampling_period");
1489 GPS_srv.request.value = 32;
1490 if (set_GPS_client.
call(GPS_srv) && GPS_srv.response.success) {
1506 if (!GPS_srv.response.success)
1507 ROS_ERROR(
"Sampling period is not valid.");
1508 ROS_ERROR(
"Failed to enable GPS.");
1515 sampling_period_GPS_client.call(sampling_period_GPS_srv);
1516 ROS_INFO(
"GPS is enabled with a sampling period of %d.", sampling_period_GPS_srv.response.value);
1519 webots_ros::get_int gps_get_coordinate_system_srv;
1520 gps_get_coordinate_system_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/gps/get_coordinate_system");
1522 gps_get_coordinate_system_client.
call(gps_get_coordinate_system_srv);
1523 ROS_INFO(
"GPS coordinate system type is: %d.", gps_get_coordinate_system_srv.response.value);
1527 sampling_period_GPS_client.call(sampling_period_GPS_srv);
1528 ROS_INFO(
"GPS is disabled (sampling period is %d).", sampling_period_GPS_srv.response.value);
1531 sampling_period_GPS_client.shutdown();
1532 gps_get_coordinate_system_client.
shutdown();
1540 webots_ros::set_int gyro_srv;
1542 set_gyro_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/gyro/enable");
1545 webots_ros::get_int sampling_period_gyro_srv;
1546 sampling_period_gyro_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/gyro/get_sampling_period");
1548 gyro_srv.request.value = 32;
1549 if (set_gyro_client.
call(gyro_srv) && gyro_srv.response.success) {
1557 if (!gyro_srv.response.success)
1558 ROS_ERROR(
"Sampling period is not valid.");
1559 ROS_ERROR(
"Failed to enable gyro.");
1566 sampling_period_gyro_client.call(sampling_period_gyro_srv);
1567 ROS_INFO(
"Gyro is enabled with a sampling period of %d.", sampling_period_gyro_srv.response.value);
1571 sampling_period_gyro_client.call(sampling_period_gyro_srv);
1572 ROS_INFO(
"Gyro is disabled (sampling period is %d).", sampling_period_gyro_srv.response.value);
1575 sampling_period_gyro_client.shutdown();
1583 webots_ros::set_int inertial_unit_srv;
1585 set_inertial_unit_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/inertial_unit/enable");
1588 webots_ros::get_int sampling_period_inertial_unit_srv;
1589 sampling_period_inertial_unit_client =
1590 n.
serviceClient<webots_ros::get_int>(model_name +
"/inertial_unit/get_sampling_period");
1592 inertial_unit_srv.request.value = 32;
1593 if (set_inertial_unit_client.
call(inertial_unit_srv) && inertial_unit_srv.response.success) {
1594 ROS_INFO(
"Inertial_unit enabled.");
1601 if (!inertial_unit_srv.response.success)
1602 ROS_ERROR(
"Sampling period is not valid.");
1603 ROS_ERROR(
"Failed to enable inertial_unit.");
1611 sampling_period_inertial_unit_client.call(sampling_period_inertial_unit_srv);
1612 ROS_INFO(
"Inertial_unit is enabled with a sampling period of %d.", sampling_period_inertial_unit_srv.response.value);
1616 sampling_period_inertial_unit_client.call(sampling_period_inertial_unit_srv);
1617 ROS_INFO(
"Inertial_unit is disabled (sampling period is %d).", sampling_period_inertial_unit_srv.response.value);
1619 set_inertial_unit_client.
shutdown();
1620 sampling_period_inertial_unit_client.shutdown();
1628 webots_ros::set_int enable_joystick_srv;
1631 enable_joystick_srv.request.value = 32;
1632 if (enable_joystick_client.
call(enable_joystick_srv) && enable_joystick_srv.response.success) {
1633 ROS_INFO(
"Joystick of %s has been enabled.", model_name.c_str());
1635 ROS_INFO(
"Topics for joystick initialized.");
1637 while (sub_joystick.getNumPublishers() == 0) {
1641 ROS_INFO(
"Topics for joystick connected.");
1643 ROS_ERROR(
"Failed to enable joystick.");
1651 webots_ros::get_string joystick_get_model_srv;
1652 joystick_get_model_client = n.
serviceClient<webots_ros::get_string>(model_name +
"/joystick/get_model");
1653 joystick_get_model_client.
call(joystick_get_model_srv);
1654 ROS_INFO(
"Got josytick model: %s.", joystick_get_model_srv.response.value.c_str());
1656 joystick_get_model_client.
shutdown();
1664 webots_ros::set_int set_led_srv;
1665 set_led_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/led/set_led");
1667 set_led_srv.request.value = 1;
1668 if (set_led_client.
call(set_led_srv) && set_led_srv.response.success)
1671 ROS_ERROR(
"Failed to call service set_led.");
1677 webots_ros::get_int get_led_srv;
1678 get_led_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/led/get_led");
1680 get_led_client.
call(get_led_srv);
1681 ROS_INFO(
"LED value is %d.", get_led_srv.response.value);
1683 set_led_srv.request.value = 0;
1684 if (set_led_client.
call(set_led_srv) && set_led_srv.response.success)
1687 ROS_ERROR(
"Failed to call service set_led.");
1699 webots_ros::set_int lidar_srv;
1702 set_lidar_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/lidar/enable");
1704 if (set_lidar_client.
call(lidar_srv) && lidar_srv.response.success) {
1707 ROS_INFO(
"Topic for lidar initialized.");
1713 ROS_INFO(
"Topic for lidar color connected.");
1715 if (!lidar_srv.response.success)
1716 ROS_ERROR(
"Sampling period is not valid.");
1717 ROS_ERROR(
"Failed to enable lidar.");
1726 get_info_client = n.
serviceClient<webots_ros::lidar_get_info>(model_name +
"/lidar/get_info");
1727 webots_ros::lidar_get_info get_lidar_info_srv;
1728 if (get_info_client.
call(get_lidar_info_srv))
1729 ROS_INFO(
"Lidar of %s has a horizontal resolution of %d, %d layers, a field of view of %f, a min range of %f and a max " 1731 model_name.c_str(), get_lidar_info_srv.response.horizontalResolution, get_lidar_info_srv.response.numberOfLayers,
1732 get_lidar_info_srv.response.fov, get_lidar_info_srv.response.minRange, get_lidar_info_srv.response.maxRange);
1734 ROS_ERROR(
"Failed to call service lidar_get_info.");
1740 get_info_client = n.
serviceClient<webots_ros::lidar_get_frequency_info>(model_name +
"/lidar/get_frequency_info");
1741 webots_ros::lidar_get_frequency_info get_lidar_frequency_info_srv;
1742 if (get_info_client.
call(get_lidar_frequency_info_srv))
1743 ROS_INFO(
"Lidar %s current frequency is %f, maximum frequency is %f and minimum frequency is %f.", model_name.c_str(),
1744 get_lidar_frequency_info_srv.response.frequency, get_lidar_frequency_info_srv.response.maxFrequency,
1745 get_lidar_frequency_info_srv.response.minFrequency);
1747 ROS_ERROR(
"Failed to call service lidar_get_frequency_info.");
1759 webots_ros::set_int light_sensor_srv;
1761 set_light_sensor_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/light_sensor/enable");
1764 webots_ros::get_int sampling_period_light_sensor_srv;
1765 sampling_period_light_sensor_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/light_sensor/get_sampling_period");
1767 light_sensor_srv.request.value = 32;
1768 if (set_light_sensor_client.
call(light_sensor_srv) && light_sensor_srv.response.success) {
1776 if (!light_sensor_srv.response.success)
1777 ROS_ERROR(
"Sampling period is not valid.");
1778 ROS_ERROR(
"Failed to enable light_sensor.");
1786 sampling_period_light_sensor_client.call(sampling_period_light_sensor_srv);
1787 ROS_INFO(
"Light_sensor is enabled with a sampling period of %d.", sampling_period_light_sensor_srv.response.value);
1791 sampling_period_light_sensor_client.call(sampling_period_light_sensor_srv);
1792 ROS_INFO(
"Light_sensor is disabled (sampling period is %d).", sampling_period_light_sensor_srv.response.value);
1794 set_light_sensor_client.
shutdown();
1795 sampling_period_light_sensor_client.shutdown();
1803 webots_ros::get_int motor_get_type_srv;
1804 motor_get_type_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/rotational_motor/get_type");
1805 motor_get_type_client.
call(motor_get_type_srv);
1806 ROS_INFO(
"Rotational_motor is of type %d.", motor_get_type_srv.response.value);
1812 webots_ros::get_int linear_motor_get_type_srv;
1813 linear_motor_get_type_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/linear_motor/get_type");
1814 linear_motor_get_type_client.
call(linear_motor_get_type_srv);
1815 ROS_INFO(
"Linear_motor is of type %d.", linear_motor_get_type_srv.response.value);
1817 linear_motor_get_type_client.
shutdown();
1822 webots_ros::get_string motor_get_brake_name_srv;
1823 motor_get_brake_name_client = n.
serviceClient<webots_ros::get_string>(model_name +
"/linear_motor/get_brake_name");
1824 if (motor_get_brake_name_client.
call(motor_get_brake_name_srv)) {
1825 ROS_INFO(
"Brake name returned from Motor API: %s.", motor_get_brake_name_srv.response.value.c_str());
1826 if (motor_get_brake_name_srv.response.value.compare(
"my_brake") != 0)
1827 ROS_ERROR(
"Failed to call service motor_get_brake_name: received '%s' instead of 'my_brake'",
1828 motor_get_brake_name_srv.response.value.c_str());
1830 ROS_ERROR(
"Failed to call service motor_get_brake_name.");
1832 motor_get_brake_name_client.
shutdown();
1836 webots_ros::set_float set_acceleration_srv;
1837 set_acceleration_client = n.
serviceClient<webots_ros::set_float>(model_name +
"/rotational_motor/set_acceleration");
1839 set_acceleration_srv.request.value = 0.5;
1840 if (set_acceleration_client.
call(set_acceleration_srv) && set_acceleration_srv.response.success)
1841 ROS_INFO(
"Acceleration set to 0.5.");
1843 ROS_ERROR(
"Failed to call service set_acceleration on motor.");
1845 set_acceleration_client.
shutdown();
1849 webots_ros::set_float set_velocity_srv;
1850 set_velocity_client = n.
serviceClient<webots_ros::set_float>(model_name +
"/rotational_motor/set_velocity");
1852 set_velocity_srv.request.value = 0.9;
1853 if (set_velocity_client.
call(set_velocity_srv) && set_velocity_srv.response.success)
1856 ROS_ERROR(
"Failed to call service set_velocity on motor.");
1862 webots_ros::set_float set_force_srv;
1863 set_force_client = n.
serviceClient<webots_ros::set_float>(model_name +
"/linear_motor/set_force");
1865 set_force_srv.request.value = 0.2;
1866 if (set_force_client.
call(set_force_srv) && set_force_srv.response.success)
1869 ROS_ERROR(
"Failed to call service set_force on motor.");
1875 webots_ros::set_float set_torque_srv;
1876 set_torque_client = n.
serviceClient<webots_ros::set_float>(model_name +
"/rotational_motor/set_torque");
1878 set_torque_srv.request.value = 0.5;
1879 if (set_torque_client.
call(set_torque_srv) && set_torque_srv.response.success)
1882 ROS_ERROR(
"Failed to call service set_torque on motor.");
1888 webots_ros::set_float set_available_force_srv;
1889 set_available_force_client = n.
serviceClient<webots_ros::set_float>(model_name +
"/linear_motor/set_available_force");
1891 set_available_force_srv.request.value = 0.8;
1892 if (set_available_force_client.
call(set_available_force_srv) && set_available_force_srv.response.success)
1893 ROS_INFO(
"Available_force set to 0.8.");
1895 ROS_ERROR(
"Failed to call service set_available_force on motor.");
1897 set_available_force_client.
shutdown();
1901 webots_ros::set_float set_available_torque_srv;
1902 set_available_torque_client = n.
serviceClient<webots_ros::set_float>(model_name +
"/rotational_motor/set_available_torque");
1904 set_available_torque_srv.request.value = 0.8;
1905 if (set_available_torque_client.
call(set_available_torque_srv) && set_available_torque_srv.response.success)
1906 ROS_INFO(
"Available_torque set to 0.8.");
1908 ROS_ERROR(
"Failed to call service set_available_torque on motor.");
1910 set_available_torque_client.
shutdown();
1914 webots_ros::motor_set_control_pid set_control_pid_srv;
1915 set_control_pid_client = n.
serviceClient<webots_ros::motor_set_control_pid>(model_name +
"/rotational_motor/set_control_pid");
1917 set_control_pid_srv.request.controlp = 1;
1918 if (set_control_pid_client.
call(set_control_pid_srv) && set_control_pid_srv.response.success == 1)
1921 ROS_ERROR(
"Failed to call service set_controlp on motor.");
1928 webots_ros::motor_set_control_pid set_linear_control_pid_srv;
1929 set_linear_control_pid_client =
1930 n.
serviceClient<webots_ros::motor_set_control_pid>(model_name +
"/linear_motor/set_control_pid");
1932 set_linear_control_pid_srv.request.controlp = 1;
1933 if (set_linear_control_pid_client.
call(set_linear_control_pid_srv) && set_linear_control_pid_srv.response.success == 1)
1934 ROS_INFO(
"Control p set to 1 for linear_motor.");
1936 ROS_ERROR(
"Failed to call service set_controlp on linear_motor.");
1938 set_linear_control_pid_client.
shutdown();
1943 webots_ros::set_float set_position_srv;
1944 set_position_client = n.
serviceClient<webots_ros::set_float>(model_name +
"/rotational_motor/set_position");
1946 set_position_srv.request.value = 1.5;
1947 if (set_position_client.
call(set_position_srv) && set_position_srv.response.success)
1950 ROS_ERROR(
"Failed to call service set_position on motor.");
1957 webots_ros::set_float set_linear_position_srv;
1958 set_linear_position_client = n.
serviceClient<webots_ros::set_float>(model_name +
"/linear_motor/set_position");
1960 set_linear_position_srv.request.value = 0.3;
1961 if (set_linear_position_client.
call(set_linear_position_srv) && set_linear_position_srv.response.success)
1962 ROS_INFO(
"Position set to 0.3 for linear_motor.");
1964 ROS_ERROR(
"Failed to call service set_position on linear_motor.");
1966 set_linear_position_client.
shutdown();
1970 webots_ros::get_float get_target_position_srv;
1971 get_target_position_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/rotational_motor/get_target_position");
1973 get_target_position_client.
call(get_target_position_srv);
1974 ROS_INFO(
"Target position for rotational_motor is %f.", get_target_position_srv.response.value);
1976 get_target_position_client.
shutdown();
1980 webots_ros::get_float get_min_position_srv;
1981 get_min_position_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/rotational_motor/get_min_position");
1983 get_min_position_client.
call(get_min_position_srv);
1984 ROS_INFO(
"Min position for rotational_motor is %f.", get_min_position_srv.response.value);
1986 get_min_position_client.
shutdown();
1990 webots_ros::get_float get_max_position_srv;
1991 get_max_position_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/rotational_motor/get_max_position");
1993 get_max_position_client.
call(get_max_position_srv);
1994 ROS_INFO(
"Max position for rotational_motor is %f.", get_max_position_srv.response.value);
1996 get_max_position_client.
shutdown();
2000 webots_ros::get_float get_velocity_srv;
2001 get_velocity_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/rotational_motor/get_velocity");
2003 get_velocity_client.
call(get_velocity_srv);
2004 ROS_INFO(
"Velocity for rotational_motor is %f.", get_velocity_srv.response.value);
2010 webots_ros::get_float get_max_velocity_srv;
2011 get_max_velocity_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/rotational_motor/get_max_velocity");
2013 get_max_velocity_client.
call(get_max_velocity_srv);
2014 ROS_INFO(
"Max velocity for rotational_motor is %f.", get_max_velocity_srv.response.value);
2016 get_max_velocity_client.
shutdown();
2020 webots_ros::get_float get_acceleration_srv;
2021 get_acceleration_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/rotational_motor/get_acceleration");
2023 get_acceleration_client.
call(get_acceleration_srv);
2024 ROS_INFO(
"Acceleration for rotational_motor is %f.", get_acceleration_srv.response.value);
2026 get_acceleration_client.
shutdown();
2030 webots_ros::get_float get_available_force_srv;
2031 get_available_force_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/rotational_motor/get_available_force");
2033 get_available_force_client.
call(get_available_force_srv);
2034 ROS_INFO(
"Available force for rotational_motor is %f.", get_available_force_srv.response.value);
2036 get_available_force_client.
shutdown();
2040 webots_ros::get_float get_max_force_srv;
2041 get_max_force_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/rotational_motor/get_max_force");
2043 get_max_force_client.
call(get_max_force_srv);
2044 ROS_INFO(
"Max force for rotational_motor is %f.", get_max_force_srv.response.value);
2050 webots_ros::get_float get_available_torque_srv;
2051 get_available_torque_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/rotational_motor/get_available_torque");
2053 get_available_torque_client.
call(get_available_torque_srv);
2054 ROS_INFO(
"Available torque for rotational_motor is %f.", get_available_torque_srv.response.value);
2056 get_available_torque_client.
shutdown();
2060 webots_ros::get_float get_max_torque_srv;
2061 get_max_torque_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/rotational_motor/get_max_torque");
2063 get_max_torque_client.
call(get_max_torque_srv);
2064 ROS_INFO(
"Max torque for rotational_motor is %f.", get_max_torque_srv.response.value);
2075 webots_ros::pen_set_ink_color set_ink_color_srv;
2076 set_ink_color_client = n.
serviceClient<webots_ros::pen_set_ink_color>(model_name +
"/pen/set_ink_color");
2078 set_ink_color_srv.request.color = 0x00FF08;
2079 if (set_ink_color_client.
call(set_ink_color_srv) && set_ink_color_srv.response.success == 1)
2080 ROS_INFO(
"Ink color set to turquoise.");
2082 ROS_ERROR(
"Failed to call service set_ink_color.");
2088 webots_ros::set_bool pen_write_srv;
2089 pen_write_client = n.
serviceClient<webots_ros::set_bool>(model_name +
"/pen/write");
2091 pen_write_srv.request.value =
true;
2092 if (pen_write_client.
call(pen_write_srv) && pen_write_srv.response.success)
2095 ROS_ERROR(
"Failed to call service pen_write.");
2106 webots_ros::set_int position_sensor_srv;
2108 set_position_sensor_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/position_sensor/enable");
2111 webots_ros::get_int sampling_period_position_sensor_srv;
2112 sampling_period_position_sensor_client =
2113 n.
serviceClient<webots_ros::get_int>(model_name +
"/position_sensor/get_sampling_period");
2115 position_sensor_srv.request.value = 32;
2116 if (set_position_sensor_client.
call(position_sensor_srv) && position_sensor_srv.response.success) {
2117 ROS_INFO(
"Position_sensor enabled.");
2124 if (!position_sensor_srv.response.success)
2125 ROS_ERROR(
"Sampling period is not valid.");
2126 ROS_ERROR(
"Failed to enable position_sensor.");
2134 sampling_period_position_sensor_client.call(sampling_period_position_sensor_srv);
2135 ROS_INFO(
"Position_sensor is enabled with a sampling period of %d.", sampling_period_position_sensor_srv.response.value);
2140 webots_ros::get_int position_sensor_get_type_srv;
2141 position_sensor_get_type_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/position_sensor/get_type");
2143 position_sensor_get_type_client.
call(position_sensor_get_type_srv);
2144 ROS_INFO(
"Position_sensor is of type %d.", position_sensor_get_type_srv.response.value);
2146 position_sensor_get_type_client.
shutdown();
2149 sampling_period_position_sensor_client.call(sampling_period_position_sensor_srv);
2150 ROS_INFO(
"Position_sensor is disabled (sampling period is %d).", sampling_period_position_sensor_srv.response.value);
2152 set_position_sensor_client.
shutdown();
2153 sampling_period_position_sensor_client.shutdown();
2162 webots_ros::set_int radar_srv;
2166 set_radar_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/radar/enable");
2168 if (set_radar_client.
call(radar_srv) && radar_srv.response.success) {
2172 ROS_INFO(
"Topics for radar initialized.");
2178 ROS_INFO(
"Topics for radar connected.");
2180 if (!radar_srv.response.success)
2181 ROS_ERROR(
"Sampling period is not valid.");
2182 ROS_ERROR(
"Failed to enable radar.");
2187 sub_radar_target_number.
shutdown();
2193 webots_ros::get_float radar_get_max_range_srv;
2194 if (radar_range_client.
call(radar_get_max_range_srv)) {
2195 if (radar_get_max_range_srv.response.value == 2.0)
2196 ROS_INFO(
"Received correct radar max range.");
2198 ROS_ERROR(
"Received wrong radar max range.");
2200 ROS_ERROR(
"Failed to call service radar_get_max_range.");
2205 radar_range_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/radar/get_min_range");
2206 webots_ros::get_float radar_get_min_range_srv;
2207 if (radar_range_client.
call(radar_get_min_range_srv)) {
2208 if (radar_get_min_range_srv.response.value == 1.0)
2209 ROS_INFO(
"Received correct radar min range.");
2211 ROS_ERROR(
"Received wrong radar min range.");
2213 ROS_ERROR(
"Failed to call service radar_get_min_range.");
2226 webots_ros::set_int range_finder_srv;
2229 set_range_finder_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/range_finder/enable");
2230 range_finder_srv.request.value =
TIME_STEP;
2231 if (set_range_finder_client.
call(range_finder_srv) && range_finder_srv.response.success) {
2234 ROS_INFO(
"Topic for range-finder initialized.");
2240 ROS_INFO(
"Topic for range-finder connected.");
2242 if (!range_finder_srv.response.success)
2243 ROS_ERROR(
"Sampling period is not valid.");
2244 ROS_ERROR(
"Failed to enable range-finder.");
2249 set_range_finder_client.
shutdown();
2253 get_info_client = n.
serviceClient<webots_ros::range_finder_get_info>(model_name +
"/range_finder/get_info");
2254 webots_ros::range_finder_get_info get_range_finder_info_srv;
2255 if (get_info_client.
call(get_range_finder_info_srv))
2257 "Range-finder of %s has a width of %d, a height of %d, a field of view of %f, a min range of %f and a max range of %f.",
2258 model_name.c_str(), get_range_finder_info_srv.response.width, get_range_finder_info_srv.response.height,
2259 get_range_finder_info_srv.response.Fov, get_range_finder_info_srv.response.minRange,
2260 get_range_finder_info_srv.response.maxRange);
2262 ROS_ERROR(
"Failed to call service range_finder_get_info.");
2268 save_image_client = n.
serviceClient<webots_ros::save_image>(model_name +
"/range_finder/save_image");
2269 webots_ros::save_image save_range_image_srv;
2270 save_range_image_srv.request.filename = std::string(getenv(
"HOME")) + std::string(
"/test_image_range_finder.png");
2271 save_range_image_srv.request.quality = 100;
2273 if (save_image_client.
call(save_range_image_srv) && save_range_image_srv.response.success == 1)
2276 ROS_ERROR(
"Failed to call service save_image.");
2281 ROS_INFO(
"Range-finder disabled.");
2288 webots_ros::set_int receiver_srv;
2290 set_receiver_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/receiver/enable");
2293 webots_ros::get_int sampling_period_receiver_srv;
2294 sampling_period_receiver_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/receiver/get_sampling_period");
2296 receiver_srv.request.value = 32;
2297 if (set_receiver_client.
call(receiver_srv) && receiver_srv.response.success) {
2305 if (!receiver_srv.response.success)
2306 ROS_ERROR(
"Sampling period is not valid.");
2307 ROS_ERROR(
"Failed to enable receiver.");
2315 sampling_period_receiver_client.call(sampling_period_receiver_srv);
2316 ROS_INFO(
"Receiver is enabled with a sampling period of %d.", sampling_period_receiver_srv.response.value);
2324 webots_ros::get_int receiver_get_data_size_srv;
2325 receiver_get_data_size_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/receiver/get_data_size");
2327 receiver_get_data_size_client.
call(receiver_get_data_size_srv);
2328 if (receiver_get_data_size_srv.response.value != -1)
2329 ROS_INFO(
"Emitter's buffer is of size %d.", receiver_get_data_size_srv.response.value);
2331 ROS_INFO(
"No message received by emitter, impossible to get buffer size.");
2333 receiver_get_data_size_client.
shutdown();
2338 webots_ros::set_int receiver_set_channel_srv;
2339 receiver_set_channel_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/receiver/set_channel");
2341 receiver_set_channel_srv.request.value = 1;
2343 if (receiver_set_channel_client.
call(receiver_set_channel_srv) && receiver_set_channel_srv.response.success)
2344 ROS_INFO(
"Receiver has update the channel.");
2346 ROS_ERROR(
"Failed to call service receiver_set_channel to update channel.");
2348 receiver_set_channel_client.
shutdown();
2353 webots_ros::get_int receiver_get_channel_srv;
2354 receiver_get_channel_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/receiver/get_channel");
2356 receiver_get_channel_client.
call(receiver_get_channel_srv);
2357 ROS_INFO(
"Receiver uses channel %d.", receiver_get_channel_srv.response.value);
2359 receiver_get_channel_client.
shutdown();
2364 webots_ros::get_int receiver_get_queue_length_srv;
2365 receiver_get_queue_length_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/receiver/get_queue_length");
2367 receiver_get_queue_length_client.
call(receiver_get_queue_length_srv);
2368 ROS_INFO(
"Length of receiver queue is %d.", receiver_get_queue_length_srv.response.value);
2370 receiver_get_queue_length_client.
shutdown();
2376 webots_ros::get_float receiver_get_signal_strength_srv;
2377 receiver_get_signal_strength_client = n.
serviceClient<webots_ros::get_float>(model_name +
"/receiver/get_signal_strength");
2379 receiver_get_signal_strength_client.
call(receiver_get_signal_strength_srv);
2380 if (receiver_get_signal_strength_srv.response.value != -1.0)
2381 ROS_INFO(
"Strength of the signal is %lf.", receiver_get_signal_strength_srv.response.value);
2383 ROS_INFO(
"No message received by emitter, impossible to get signal strength.");
2385 receiver_get_signal_strength_client.
shutdown();
2391 webots_ros::receiver_get_emitter_direction receiver_get_emitter_direction_srv;
2392 receiver_get_emitter_direction_client =
2393 n.
serviceClient<webots_ros::receiver_get_emitter_direction>(model_name +
"/receiver/get_emitter_direction");
2395 receiver_get_emitter_direction_client.
call(receiver_get_emitter_direction_srv);
2396 if (receiver_get_emitter_direction_srv.response.direction[0] != 0 ||
2397 receiver_get_emitter_direction_srv.response.direction[1] != 0 ||
2398 receiver_get_emitter_direction_srv.response.direction[2] != 0)
2399 ROS_INFO(
"Signal from emitter comes from direction {%f. %f, %f}.", receiver_get_emitter_direction_srv.response.direction[0],
2400 receiver_get_emitter_direction_srv.response.direction[1],
2401 receiver_get_emitter_direction_srv.response.direction[2]);
2403 ROS_INFO(
"No message received by emitter, impossible to get signal direction.");
2405 receiver_get_emitter_direction_client.
shutdown();
2411 webots_ros::get_bool receiver_next_packet_srv;
2412 receiver_next_packet_client = n.
serviceClient<webots_ros::get_bool>(model_name +
"/receiver/next_packet");
2414 if (receiver_next_packet_client.
call(receiver_next_packet_srv) && receiver_next_packet_srv.response.value)
2415 ROS_INFO(
"Next packet is ready to be read.");
2416 else if (!receiver_next_packet_srv.response.value)
2417 ROS_INFO(
"No message received by emitter, impossible to get next packet.");
2419 ROS_ERROR(
"Failed to call service receiver_next_packet.");
2421 receiver_next_packet_client.
shutdown();
2424 sampling_period_receiver_client.call(sampling_period_receiver_srv);
2425 ROS_INFO(
"Receiver is disabled (sampling period is %d).", sampling_period_receiver_srv.response.value);
2427 sampling_period_receiver_client.shutdown();
2435 webots_ros::set_int touch_sensor_srv;
2437 set_touch_sensor_client = n.
serviceClient<webots_ros::set_int>(model_name +
"/touch_sensor/enable");
2440 webots_ros::get_int sampling_period_touch_sensor_srv;
2441 sampling_period_touch_sensor_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/touch_sensor/get_sampling_period");
2444 webots_ros::get_int touch_sensor_get_type_srv;
2445 touch_sensor_get_type_client = n.
serviceClient<webots_ros::get_int>(model_name +
"/touch_sensor/get_type");
2447 touch_sensor_get_type_client.
call(touch_sensor_get_type_srv);
2448 ROS_INFO(
"Touch_sensor is of type %d.", touch_sensor_get_type_srv.response.value);
2450 touch_sensor_get_type_client.shutdown();
2453 touch_sensor_srv.request.value = 32;
2454 if (set_touch_sensor_client.
call(touch_sensor_srv) && touch_sensor_srv.response.success) {
2456 if (touch_sensor_get_type_srv.response.value == 0)
2458 else if (touch_sensor_get_type_srv.response.value == 1)
2467 if (!touch_sensor_srv.response.success)
2468 ROS_ERROR(
"Sampling period is not valid.");
2469 ROS_ERROR(
"Failed to enable touch_sensor.");
2477 sampling_period_touch_sensor_client.call(sampling_period_touch_sensor_srv);
2478 ROS_INFO(
"Touch_sensor is enabled with a sampling period of %d.", sampling_period_touch_sensor_srv.response.value);
2482 sampling_period_touch_sensor_client.call(sampling_period_touch_sensor_srv);
2483 ROS_INFO(
"Touch_sensor is disabled (sampling period is %d).", sampling_period_touch_sensor_srv.response.value);
2485 set_touch_sensor_client.
shutdown();
2486 sampling_period_touch_sensor_client.shutdown();
2494 webots_ros::get_bool supervisor_simulation_reset_physics_srv;
2495 supervisor_simulation_reset_physics_client =
2496 n.
serviceClient<webots_ros::get_bool>(model_name +
"/supervisor/simulation_reset_physics");
2498 if (supervisor_simulation_reset_physics_client.
call(supervisor_simulation_reset_physics_srv) &&
2499 supervisor_simulation_reset_physics_srv.response.value)
2500 ROS_INFO(
"Simulation has reset_physics successfully.");
2502 ROS_ERROR(
"Failed to call service simulation_reset_physics.");
2504 supervisor_simulation_reset_physics_client.
shutdown();
2508 webots_ros::save_image supervisor_export_image_srv;
2509 supervisor_export_image_client = n.
serviceClient<webots_ros::save_image>(model_name +
"/supervisor/export_image");
2511 supervisor_export_image_srv.request.filename = std::string(getenv(
"HOME")) + std::string(
"/main_window_test.jpg");
2512 supervisor_export_image_srv.request.quality = 100;
2513 if (supervisor_export_image_client.
call(supervisor_export_image_srv) && supervisor_export_image_srv.response.success == 1)
2514 ROS_INFO(
"Image from main window saved successfully.");
2516 ROS_ERROR(
"Failed to call service export_image.");
2518 supervisor_export_image_client.
shutdown();
2522 webots_ros::supervisor_set_label supervisor_set_label_srv;
2523 supervisor_set_label_client = n.
serviceClient<webots_ros::supervisor_set_label>(model_name +
"/supervisor/set_label");
2525 supervisor_set_label_srv.request.id = 1;
2526 supervisor_set_label_srv.request.label =
"This is a label";
2527 supervisor_set_label_srv.request.xpos = 0.02;
2528 supervisor_set_label_srv.request.ypos = 0.2;
2529 supervisor_set_label_srv.request.size = 0.1;
2530 supervisor_set_label_srv.request.color = 0XFF0000;
2531 supervisor_set_label_srv.request.transparency = 0;
2532 supervisor_set_label_srv.request.font =
"Lucida Console";
2533 if (supervisor_set_label_client.
call(supervisor_set_label_srv) && supervisor_set_label_srv.response.success == 1)
2534 ROS_INFO(
"Label set successfully.");
2536 ROS_ERROR(
"Failed to call service set_label.");
2541 webots_ros::get_uint64 supervisor_get_root_srv;
2542 supervisor_get_root_client = n.
serviceClient<webots_ros::get_uint64>(model_name +
"/supervisor/get_root");
2544 supervisor_get_root_client.
call(supervisor_get_root_srv);
2545 ROS_INFO(
"Got root node: %lu.", supervisor_get_root_srv.response.value);
2546 uint64_t root_node = supervisor_get_root_srv.response.value;
2548 supervisor_get_root_client.
shutdown();
2552 webots_ros::get_uint64 supervisor_get_self_srv;
2553 supervisor_get_self_client = n.
serviceClient<webots_ros::get_uint64>(model_name +
"/supervisor/get_self");
2555 supervisor_get_self_client.
call(supervisor_get_self_srv);
2556 ROS_INFO(
"Got self node: %lu.", supervisor_get_self_srv.response.value);
2557 uint64_t self_node = supervisor_get_self_srv.response.value;
2559 supervisor_get_self_client.
shutdown();
2563 webots_ros::supervisor_get_from_def supervisor_get_from_def_srv;
2564 supervisor_get_from_def_client =
2565 n.
serviceClient<webots_ros::supervisor_get_from_def>(model_name +
"/supervisor/get_from_def");
2567 supervisor_get_from_def_srv.request.name =
"TEST";
2568 supervisor_get_from_def_client.
call(supervisor_get_from_def_srv);
2569 uint64_t from_def_node = 0;
2570 if (supervisor_get_from_def_srv.response.node != 0) {
2571 ROS_INFO(
"Got from DEF node: %ld.", supervisor_get_from_def_srv.response.node);
2572 from_def_node = supervisor_get_from_def_srv.response.node;
2574 ROS_ERROR(
"Could not get node from DEF.");
2579 webots_ros::node_get_type supervisor_node_get_type_srv;
2580 supervisor_node_get_type_client = n.
serviceClient<webots_ros::node_get_type>(model_name +
"/supervisor/node/get_type");
2582 supervisor_node_get_type_srv.request.node = from_def_node;
2583 supervisor_node_get_type_client.
call(supervisor_node_get_type_srv);
2584 ROS_INFO(
"Got node type: %d.", supervisor_node_get_type_srv.response.type);
2586 supervisor_node_get_type_client.
shutdown();
2590 webots_ros::node_get_name supervisor_node_get_type_name_srv;
2591 supervisor_node_get_type_name_client =
2592 n.
serviceClient<webots_ros::node_get_name>(model_name +
"/supervisor/node/get_type_name");
2594 supervisor_node_get_type_name_srv.request.node = from_def_node;
2595 supervisor_node_get_type_name_client.
call(supervisor_node_get_type_name_srv);
2596 ROS_INFO(
"Got node type name: %s.", supervisor_node_get_type_name_srv.response.name.c_str());
2598 supervisor_node_get_type_name_srv.request.node = root_node;
2599 supervisor_node_get_type_name_client.
call(supervisor_node_get_type_name_srv);
2600 ROS_INFO(
"Got type name of root node: %s.", supervisor_node_get_type_name_srv.response.name.c_str());
2602 supervisor_node_get_type_name_srv.request.node = self_node;
2603 supervisor_node_get_type_name_client.
call(supervisor_node_get_type_name_srv);
2604 ROS_INFO(
"Got type name of self node: %s.", supervisor_node_get_type_name_srv.response.name.c_str());
2606 supervisor_get_from_def_srv.request.name =
"GROUND";
2607 supervisor_get_from_def_client.
call(supervisor_get_from_def_srv);
2608 uint64_t ground_node = 0;
2609 if (supervisor_get_from_def_srv.response.node != 0) {
2610 ROS_INFO(
"Got from DEF GROUND node: %ld.", supervisor_get_from_def_srv.response.node);
2611 ground_node = supervisor_get_from_def_srv.response.node;
2613 ROS_ERROR(
"Could not get node from DEF GROUND.");
2615 supervisor_node_get_type_name_srv.request.node = ground_node;
2616 supervisor_node_get_type_name_client.
call(supervisor_node_get_type_name_srv);
2617 ROS_INFO(
"Got type name of GROUND node: %s.", supervisor_node_get_type_name_srv.response.name.c_str());
2622 webots_ros::node_get_name supervisor_node_get_base_type_name_srv;
2623 supervisor_node_get_base_type_name_client =
2624 n.
serviceClient<webots_ros::node_get_name>(model_name +
"/supervisor/node/get_base_type_name");
2625 supervisor_node_get_base_type_name_srv.request.node = ground_node;
2626 supervisor_node_get_base_type_name_client.
call(supervisor_node_get_base_type_name_srv);
2627 ROS_INFO(
"Got base type name of GROUND node: %s.", supervisor_node_get_base_type_name_srv.response.name.c_str());
2629 supervisor_node_get_base_type_name_client.
shutdown();
2633 webots_ros::node_get_name supervisor_node_get_def_srv;
2634 supervisor_node_get_def_client = n.
serviceClient<webots_ros::node_get_name>(model_name +
"/supervisor/node/get_def");
2635 supervisor_node_get_def_srv.request.node = ground_node;
2636 supervisor_node_get_def_client.
call(supervisor_node_get_def_srv);
2637 ROS_INFO(
"Got DEF name of GROUND node: %s.", supervisor_node_get_def_srv.response.name.c_str());
2639 supervisor_node_get_def_client.
shutdown();
2643 webots_ros::node_get_position supervisor_node_get_position_srv;
2644 supervisor_node_get_position_client =
2645 n.
serviceClient<webots_ros::node_get_position>(model_name +
"/supervisor/node/get_position");
2647 supervisor_node_get_position_srv.request.node = from_def_node;
2648 supervisor_node_get_position_client.
call(supervisor_node_get_position_srv);
2649 ROS_INFO(
"From_def node got position: x = %f y = %f z = %f.", supervisor_node_get_position_srv.response.position.x,
2650 supervisor_node_get_position_srv.response.position.y, supervisor_node_get_position_srv.response.position.z);
2652 supervisor_node_get_position_client.
shutdown();
2656 webots_ros::node_get_orientation supervisor_node_get_orientation_srv;
2657 supervisor_node_get_orientation_client =
2658 n.
serviceClient<webots_ros::node_get_orientation>(model_name +
"/supervisor/node/get_orientation");
2660 supervisor_node_get_orientation_srv.request.node = from_def_node;
2661 supervisor_node_get_orientation_client.
call(supervisor_node_get_orientation_srv);
2663 "From_def orientation quaternion is:\nw=%f x=%f y=%f z=%f.", supervisor_node_get_orientation_srv.response.orientation.w,
2664 supervisor_node_get_orientation_srv.response.orientation.x, supervisor_node_get_orientation_srv.response.orientation.y,
2665 supervisor_node_get_orientation_srv.response.orientation.z);
2667 supervisor_node_get_orientation_client.
shutdown();
2671 webots_ros::node_get_center_of_mass supervisor_node_get_center_of_mass_srv;
2672 supervisor_node_get_center_of_mass_client =
2673 n.
serviceClient<webots_ros::node_get_center_of_mass>(model_name +
"/supervisor/node/get_center_of_mass");
2675 supervisor_node_get_center_of_mass_srv.request.node = from_def_node;
2676 supervisor_node_get_center_of_mass_client.
call(supervisor_node_get_center_of_mass_srv);
2677 ROS_INFO(
"From_def node's center of mass coordinates are: x = %f y = %f z = %f.",
2678 supervisor_node_get_center_of_mass_srv.response.centerOfMass.x,
2679 supervisor_node_get_center_of_mass_srv.response.centerOfMass.y,
2680 supervisor_node_get_center_of_mass_srv.response.centerOfMass.z);
2682 supervisor_node_get_center_of_mass_client.
shutdown();
2686 webots_ros::node_get_number_of_contact_points supervisor_node_get_number_of_contact_points_srv;
2687 supervisor_node_get_number_of_contact_points_client = n.
serviceClient<webots_ros::node_get_number_of_contact_points>(
2688 model_name +
"/supervisor/node/get_number_of_contact_points");
2690 supervisor_node_get_number_of_contact_points_srv.request.node = from_def_node;
2691 supervisor_node_get_number_of_contact_points_client.
call(supervisor_node_get_number_of_contact_points_srv);
2692 ROS_INFO(
"From_def node got %d contact points.",
2693 supervisor_node_get_number_of_contact_points_srv.response.numberOfContactPoints);
2695 supervisor_node_get_number_of_contact_points_client.
shutdown();
2699 webots_ros::node_get_contact_point supervisor_node_get_contact_point_srv;
2700 supervisor_node_get_contact_point_client =
2701 n.
serviceClient<webots_ros::node_get_contact_point>(model_name +
"/supervisor/node/get_contact_point");
2703 supervisor_node_get_contact_point_srv.request.node = from_def_node;
2704 supervisor_node_get_contact_point_srv.request.index = 0;
2705 supervisor_node_get_contact_point_client.
call(supervisor_node_get_contact_point_srv);
2706 ROS_INFO(
"From_def_node first contact point is at x = %f, y = %f z = %f.",
2707 supervisor_node_get_contact_point_srv.response.point.x, supervisor_node_get_contact_point_srv.response.point.y,
2708 supervisor_node_get_contact_point_srv.response.point.z);
2710 supervisor_node_get_contact_point_client.
shutdown();
2716 webots_ros::node_get_static_balance supervisor_node_get_static_balance_srv;
2717 supervisor_node_get_static_balance_client =
2718 n.
serviceClient<webots_ros::node_get_static_balance>(model_name +
"/supervisor/node/get_static_balance");
2720 supervisor_node_get_static_balance_srv.request.node = from_def_node;
2721 supervisor_node_get_static_balance_client.
call(supervisor_node_get_static_balance_srv);
2722 ROS_INFO(
"From_def node balance is %d.", supervisor_node_get_static_balance_srv.response.balance);
2724 supervisor_node_get_static_balance_client.
shutdown();
2730 n.
serviceClient<webots_ros::node_reset_functions>(model_name +
"/supervisor/node/reset_physics");
2731 webots_ros::node_reset_functions supervisor_node_reset_physics_srv;
2733 supervisor_node_reset_physics_srv.request.node = from_def_node;
2734 if (supervisor_node_reset_physics_client.
call(supervisor_node_reset_physics_srv) &&
2735 supervisor_node_reset_physics_srv.response.success == 1)
2736 ROS_INFO(
"Node physics has been reset successfully.");
2738 ROS_ERROR(
"Failed to call service node_reset_physics.");
2740 supervisor_node_reset_physics_client.
shutdown();
2745 n.
serviceClient<webots_ros::node_reset_functions>(model_name +
"/supervisor/node/restart_controller");
2746 webots_ros::node_reset_functions supervisor_node_restart_controller_srv;
2748 supervisor_node_restart_controller_srv.request.node = from_def_node;
2749 if (supervisor_node_restart_controller_client.
call(supervisor_node_restart_controller_srv) &&
2750 supervisor_node_restart_controller_srv.response.success == 1)
2751 ROS_INFO(
"Robot controller has been restarted successfully.");
2753 ROS_ERROR(
"Failed to call service node_restart_controller.");
2755 supervisor_node_restart_controller_client.
shutdown();
2759 webots_ros::node_get_field supervisor_node_get_field_srv;
2760 supervisor_node_get_field_client = n.
serviceClient<webots_ros::node_get_field>(model_name +
"/supervisor/node/get_field");
2762 supervisor_node_get_field_srv.request.node = root_node;
2763 supervisor_node_get_field_srv.request.fieldName =
"children";
2764 supervisor_node_get_field_client.
call(supervisor_node_get_field_srv);
2765 uint64_t field = supervisor_node_get_field_srv.response.field;
2767 supervisor_node_get_field_client.
shutdown();
2771 webots_ros::field_get_type supervisor_field_get_type_srv;
2772 supervisor_field_get_type_client = n.
serviceClient<webots_ros::field_get_type>(model_name +
"/supervisor/field/get_type");
2774 supervisor_field_get_type_srv.request.field = field;
2775 supervisor_field_get_type_client.
call(supervisor_field_get_type_srv);
2776 ROS_INFO(
"World's children field is of type %d.", supervisor_field_get_type_srv.response.type);
2778 supervisor_field_get_type_client.
shutdown();
2782 webots_ros::field_get_type_name supervisor_field_get_type_name_srv;
2783 supervisor_field_get_type_name_client =
2784 n.
serviceClient<webots_ros::field_get_type_name>(model_name +
"/supervisor/field/get_type_name");
2786 supervisor_field_get_type_name_srv.request.field = field;
2787 supervisor_field_get_type_name_client.
call(supervisor_field_get_type_name_srv);
2788 ROS_INFO(
"Also known as %s.", supervisor_field_get_type_name_srv.response.name.c_str());
2790 supervisor_field_get_type_name_client.
shutdown();
2794 webots_ros::field_get_count supervisor_field_get_count_srv;
2795 supervisor_field_get_count_client = n.
serviceClient<webots_ros::field_get_count>(model_name +
"/supervisor/field/get_count");
2797 supervisor_field_get_count_srv.request.field = field;
2798 supervisor_field_get_count_client.
call(supervisor_field_get_count_srv);
2799 if (supervisor_field_get_count_srv.response.count != -1)
2800 ROS_INFO(
"There is %d nodes in this field.", supervisor_field_get_count_srv.response.count);
2802 ROS_ERROR(
"Illegal call to Field::getCount() argument must be multiple fields.");
2804 supervisor_field_get_count_client.
shutdown();
2807 supervisor_node_get_field_srv.request.node = from_def_node;
2808 supervisor_node_get_field_srv.request.fieldName =
"name";
2809 supervisor_node_get_field_client.
call(supervisor_node_get_field_srv);
2810 field = supervisor_node_get_field_srv.response.field;
2813 webots_ros::field_set_string supervisor_field_set_string_srv;
2814 supervisor_field_set_string_client =
2815 n.
serviceClient<webots_ros::field_set_string>(model_name +
"/supervisor/field/set_string");
2817 supervisor_field_set_string_srv.request.field = field;
2818 supervisor_field_set_string_srv.request.value =
"solid_test";
2819 if (supervisor_field_set_string_client.
call(supervisor_field_set_string_srv) &&
2820 supervisor_field_set_string_srv.response.success == 1)
2821 ROS_INFO(
"Field's string updated to: 'solid_test'.");
2823 ROS_ERROR(
"Failed to call service field_set_string.");
2825 supervisor_field_set_string_client.
shutdown();
2829 webots_ros::field_get_string supervisor_field_get_string_srv;
2830 supervisor_field_get_string_client =
2831 n.
serviceClient<webots_ros::field_get_string>(model_name +
"/supervisor/field/get_string");
2833 supervisor_field_get_string_srv.request.field = field;
2834 supervisor_field_get_string_client.
call(supervisor_field_get_string_srv);
2835 ROS_INFO(
"Field contains \"%s\".", supervisor_field_get_string_srv.response.value.c_str());
2837 supervisor_field_get_string_client.
shutdown();
2840 supervisor_node_get_field_srv.request.node = root_node;
2841 supervisor_node_get_field_srv.request.fieldName =
"children";
2842 supervisor_node_get_field_client.
call(supervisor_node_get_field_srv);
2843 field = supervisor_node_get_field_srv.response.field;
2846 webots_ros::field_get_node supervisor_field_get_node_srv;
2847 supervisor_field_get_node_client = n.
serviceClient<webots_ros::field_get_node>(model_name +
"/supervisor/field/get_node");
2849 supervisor_field_get_node_srv.request.field = field;
2850 supervisor_field_get_node_srv.request.index = 7;
2851 supervisor_field_get_node_client.
call(supervisor_field_get_node_srv);
2853 supervisor_node_get_type_name_srv.request.node = supervisor_field_get_node_srv.response.node;
2854 supervisor_node_get_type_name_client.
call(supervisor_node_get_type_name_srv);
2855 ROS_INFO(
"Node got from field_get_node is of type %s.", supervisor_node_get_type_name_srv.response.name.c_str());
2858 supervisor_get_from_def_srv.request.name =
"CONE";
2859 supervisor_get_from_def_client.
call(supervisor_get_from_def_srv);
2860 uint64_t cone_node = 0;
2861 if (supervisor_get_from_def_srv.response.node != 0) {
2862 ROS_INFO(
"Got CONE node from DEF: %lu.", supervisor_get_from_def_srv.response.node);
2863 cone_node = supervisor_get_from_def_srv.response.node;
2865 ROS_ERROR(
"could not get CONE node from DEF.");
2867 supervisor_node_get_type_name_client.
shutdown();
2868 supervisor_get_from_def_client.
shutdown();
2869 supervisor_field_get_node_client.
shutdown();
2873 webots_ros::node_get_id node_get_id_srv;
2874 node_get_id_client = n.
serviceClient<webots_ros::node_get_id>(model_name +
"/supervisor/node/get_id");
2875 node_get_id_srv.request.node = cone_node;
2876 node_get_id_client.
call(node_get_id_srv);
2877 int cone_node_id = node_get_id_srv.response.id;
2878 if (cone_node_id > 0)
2879 ROS_INFO(
"Node id got successfully.");
2881 ROS_ERROR(
"Failed to call service node_get_id.");
2887 webots_ros::supervisor_get_from_id supervisor_get_from_id_srv;
2888 node_get_id_client = n.
serviceClient<webots_ros::supervisor_get_from_id>(model_name +
"/supervisor/get_from_id");
2889 supervisor_get_from_id_srv.request.id = cone_node_id;
2890 node_get_id_client.
call(supervisor_get_from_id_srv);
2891 uint64_t cone_node_copy = supervisor_get_from_id_srv.response.node;
2892 if (cone_node_copy == cone_node)
2893 ROS_INFO(
"Cone node got successfully from id.");
2895 ROS_ERROR(
"Failed to call service supervisor_get_from_id.");
2902 webots_ros::node_set_velocity node_set_velocity_srv;
2903 node_velocity_client = n.
serviceClient<webots_ros::node_set_velocity>(model_name +
"/supervisor/node/set_velocity");
2904 node_set_velocity_srv.request.node = cone_node;
2905 node_set_velocity_srv.request.velocity.linear.x = 0.0;
2906 node_set_velocity_srv.request.velocity.linear.y = 0.0;
2907 node_set_velocity_srv.request.velocity.linear.z = 1.0;
2908 node_set_velocity_srv.request.velocity.angular.x = 0.0;
2909 node_set_velocity_srv.request.velocity.angular.y = 0.0;
2910 node_set_velocity_srv.request.velocity.angular.z = 0.0;
2911 if (node_velocity_client.
call(node_set_velocity_srv) && node_set_velocity_srv.response.success == 1)
2912 ROS_INFO(
"Node velocity set successfully.");
2914 ROS_ERROR(
"Failed to call service node_set_velocity.");
2920 webots_ros::node_get_velocity node_get_velocity_srv;
2921 node_velocity_client = n.
serviceClient<webots_ros::node_get_velocity>(model_name +
"/supervisor/node/get_velocity");
2922 node_get_velocity_srv.request.node = cone_node;
2923 node_velocity_client.
call(node_get_velocity_srv);
2924 if (node_get_velocity_srv.response.velocity.linear.z > 0.8)
2925 ROS_INFO(
"Node velocity get successfully.");
2927 ROS_ERROR(
"Failed to call service node_get_velocity.");
2934 webots_ros::node_get_parent_node node_get_parent_node_srv;
2935 node_get_parent_node_client =
2936 n.
serviceClient<webots_ros::node_get_parent_node>(model_name +
"/supervisor/node/get_parent_node");
2937 node_get_parent_node_srv.request.node = cone_node;
2938 node_get_parent_node_client.
call(node_get_parent_node_srv);
2939 if (node_get_parent_node_srv.response.node == root_node)
2940 ROS_INFO(
"Node parent got successfully.");
2942 ROS_ERROR(
"Failed to call service node_get_parent_node.");
2944 node_get_parent_node_client.
shutdown();
2949 webots_ros::node_get_status supervisor_movie_is_ready_srv;
2950 supervisor_movie_is_ready_client = n.
serviceClient<webots_ros::node_get_status>(model_name +
"/supervisor/movie_is_ready");
2952 if (supervisor_movie_is_ready_client.
call(supervisor_movie_is_ready_srv) &&
2953 supervisor_movie_is_ready_srv.response.status == 1)
2954 ROS_INFO(
"Ready to record a movie.");
2956 ROS_ERROR(
"Failed to call service supervisor_movie_is_ready.");
2958 supervisor_movie_is_ready_client.
shutdown();
2962 webots_ros::supervisor_movie_start_recording supervisor_movie_start_srv;
2963 supervisor_movie_start_client =
2964 n.
serviceClient<webots_ros::supervisor_movie_start_recording>(model_name +
"/supervisor/movie_start_recording");
2966 supervisor_movie_start_srv.request.filename = std::string(getenv(
"HOME")) + std::string(
"/movie_test.mp4");
2967 supervisor_movie_start_srv.request.width = 480;
2968 supervisor_movie_start_srv.request.height = 360;
2969 supervisor_movie_start_srv.request.codec = 1337;
2970 supervisor_movie_start_srv.request.quality = 100;
2971 supervisor_movie_start_srv.request.acceleration = 1;
2972 supervisor_movie_start_srv.request.caption =
false;
2973 if (supervisor_movie_start_client.
call(supervisor_movie_start_srv) && supervisor_movie_start_srv.response.success == 1)
2974 ROS_INFO(
"Movie started successfully.");
2976 ROS_ERROR(
"Failed to call service movie_start_recording.");
2978 supervisor_movie_start_client.
shutdown();
2979 for (
int i = 0; i < 25; ++i)
2983 webots_ros::get_bool supervisor_movie_stop_srv;
2984 supervisor_movie_stop_client = n.
serviceClient<webots_ros::get_bool>(model_name +
"/supervisor/movie_stop_recording");
2986 if (supervisor_movie_stop_client.
call(supervisor_movie_stop_srv) && supervisor_movie_stop_srv.response.value)
2987 ROS_INFO(
"Movie stopped successfully.");
2989 ROS_ERROR(
"Failed to call service movie_stop_recording.");
2991 supervisor_movie_stop_client.
shutdown();
2995 webots_ros::node_get_status supervisor_movie_failed_srv;
2996 supervisor_movie_failed_client = n.
serviceClient<webots_ros::node_get_status>(model_name +
"/supervisor/movie_failed");
2998 if (supervisor_movie_failed_client.
call(supervisor_movie_failed_srv) && supervisor_movie_failed_srv.response.status == 0)
2999 ROS_INFO(
"Movie recording executing successfully.");
3001 ROS_ERROR(
"Failed movie recording.");
3003 supervisor_movie_failed_client.
shutdown();
3006 supervisor_set_label_srv.request.label =
"";
3007 supervisor_set_label_client.
call(supervisor_set_label_srv);
3009 supervisor_set_label_client.
shutdown();
3014 webots_ros::field_remove field_remove_srv;
3015 remove_node_client = n.
serviceClient<webots_ros::field_remove>(model_name +
"/supervisor/field/remove");
3016 field_remove_srv.request.field = field;
3017 field_remove_srv.request.index = 5;
3018 if (remove_node_client.
call(field_remove_srv) && field_remove_srv.response.success == 1)
3019 ROS_INFO(
"Field node removed successfully.");
3021 ROS_ERROR(
"Failed to call service field_remove.");
3027 webots_ros::node_remove node_remove_srv;
3028 remove_node_client = n.
serviceClient<webots_ros::node_remove>(model_name +
"/supervisor/node/remove");
3029 node_remove_srv.request.node = cone_node;
3030 remove_node_client.
call(node_remove_srv);
3031 int success1 = node_remove_srv.response.success;
3033 ROS_INFO(
"Node removed successfully.");
3035 ROS_ERROR(
"Failed to call service node_removed.");
3042 wwi_send_client = n.
serviceClient<webots_ros::set_string>(model_name +
"/robot/wwi_send_text");
3043 webots_ros::set_string wwi_send_srv;
3044 wwi_send_srv.request.value =
"test wwi functions from complete_test controller.";
3045 if (wwi_send_client.
call(wwi_send_srv) && wwi_send_srv.response.success == 1)
3046 ROS_INFO(
"Text to robot window successfully sent.");
3048 ROS_ERROR(
"Failed to call service robot/wwi_send_text.");
3054 wwi_receive_client = n.
serviceClient<webots_ros::get_string>(model_name +
"/robot/wwi_receive_text");
3055 webots_ros::get_string wwi_receive_srv;
3056 if (wwi_receive_client.
call(wwi_receive_srv) &&
3057 wwi_receive_srv.response.value.compare(
"Answer: test wwi functions from complete_test controller.") == 0)
3058 ROS_INFO(
"Text from robot window successfully received.");
3060 ROS_ERROR(
"Failed to call service robot/wwi_receive_text.");
3067 webots_ros::get_bool supervisor_virtual_reality_headset_is_used_srv;
3068 virtual_reality_headset_client =
3069 n.
serviceClient<webots_ros::get_bool>(model_name +
"/supervisor/vitual_reality_headset_is_used");
3070 virtual_reality_headset_client.
call(supervisor_virtual_reality_headset_is_used_srv);
3071 bool used = supervisor_virtual_reality_headset_is_used_srv.response.value;
3074 ROS_INFO(
"No virtual reality headset connected.");
3076 ROS_ERROR(
"Virtual reality headset wrongly detected.");
3078 virtual_reality_headset_client.
shutdown();
3125 ROS_INFO(
"Robot's time step called to end tests.");
3127 ROS_ERROR(
"Failed to call service time_step to end tests.");
3133 printf(
"\nTest Completed\n");
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void lightSensorCallback(const sensor_msgs::Illuminance::ConstPtr &value)
double inertialUnitValues[4]
void joystickCallback(const webots_ros::Int8Stamped::ConstPtr &value)
void gyroCallback(const sensor_msgs::Imu::ConstPtr &values)
void receiverCallback(const webots_ros::StringStamped::ConstPtr &value)
void battery_sensorCallback(const webots_ros::Float64Stamped::ConstPtr &value)
int main(int argc, char **argv)
void lidarCallback(const sensor_msgs::Image::ConstPtr &image)
double accelerometerValues[3]
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void distance_sensorCallback(const sensor_msgs::Range::ConstPtr &value)
webots_ros::set_int time_step_srv
void keyboardCallback(const webots_ros::Int32Stamped::ConstPtr &value)
double touchSensorValues[3]
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
void connectorCallback(const webots_ros::Int8Stamped::ConstPtr &value)
void GPSCallback(const sensor_msgs::NavSatFix::ConstPtr &values)
void modelNameCallback(const std_msgs::String::ConstPtr &name)
ros::ServiceClient time_step_client
void accelerometerCallback(const sensor_msgs::Imu::ConstPtr &values)
void touchSensorBumperCallback(const webots_ros::BoolStamped::ConstPtr &value)
void rangeFinderCallback(const sensor_msgs::Image::ConstPtr &image)
void touchSensorCallback(const webots_ros::Float64Stamped::ConstPtr &value)
void radarTargetsNumberCallback(const webots_ros::Int8Stamped::ConstPtr &value)
uint32_t getNumPublishers() const
static vector< string > model_list
void positionSensorCallback(const webots_ros::Float64Stamped::ConstPtr &value)
void inertialUnitCallback(const sensor_msgs::Imu::ConstPtr &values)
void motorSensorCallback(const std_msgs::Float64::ConstPtr &value)
void cameraCallback(const sensor_msgs::Image::ConstPtr &values)
vector< unsigned char > imageColor
ROSCPP_DECL void shutdown()
void GPSSpeedCallback(const webots_ros::Float64Stamped::ConstPtr &value)
std::vector< unsigned char > image
void touchSensor3DCallback(const geometry_msgs::WrenchStamped::ConstPtr &values)
ROSCPP_DECL void spinOnce()
vector< float > imageRangeFinder
void compassCallback(const sensor_msgs::MagneticField::ConstPtr &values)
void radarTargetsCallback(const webots_ros::RadarTarget::ConstPtr &target)