18 #include <sensor_msgs/Image.h>
19 #include <std_msgs/String.h>
21 #include <webots_ros/get_float.h>
22 #include <webots_ros/set_float.h>
23 #include <webots_ros/set_int.h>
25 #include <webots_ros/range_finder_get_info.h>
26 #include <webots_ros/robot_get_device_list.h>
27 #include <webots_ros/save_image.h>
50 const float *depth_data =
reinterpret_cast<const float *
>(&
image->data[0]);
51 for (
int i = 0; i <
size; ++i)
58 ROS_INFO(
"User stopped the 'catch_the_bird' node.");
63 int main(
int argc,
char **argv) {
65 std::vector<std::string> deviceList;
68 bool birdCatched =
false;
89 int wantedController = 0;
90 std::cout <<
"Choose the # of the controller you want to use:\n";
91 std::cin >> wantedController;
95 ROS_ERROR(
"Invalid number for controller choice.");
106 webots_ros::robot_get_device_list deviceListSrv;
108 if (deviceListClient.
call(deviceListSrv))
109 deviceList = deviceListSrv.response.list;
111 ROS_ERROR(
"Failed to call service device_list.");
112 motorName = deviceList[0];
113 rangeFinderName = deviceList[1];
117 webots_ros::range_finder_get_info rangeFinderGetInfoSrv;
118 if (rangeFinderGetInfoClient.
call(rangeFinderGetInfoSrv)) {
119 width = rangeFinderGetInfoSrv.response.width;
120 height = rangeFinderGetInfoSrv.response.height;
121 ROS_INFO(
"Range-finder size is %d x %d.", width, height);
123 ROS_ERROR(
"Failed to call service range_finder_get_info.");
128 webots_ros::set_int enableRangeFinderSrv;
131 enableRangeFinderSrv.request.value = 2 *
TIME_STEP;
132 if (enableRangeFinderClient.
call(enableRangeFinderSrv) && enableRangeFinderSrv.response.success) {
133 ROS_INFO(
"Range-finder enabled with sampling period %d.", enableRangeFinderSrv.request.value);
140 ROS_ERROR(
"Failed to call service enable for %s.", rangeFinderName.c_str());
144 webots_ros::save_image rangeFinderSaveImageSrv;
145 rangeFinderSaveImageSrv.request.filename = std::string(getenv(
"HOME")) + std::string(
"/bird_catched.png");
146 rangeFinderSaveImageSrv.request.quality = 100;
151 webots_ros::set_float motorSetPositionSrv;
152 motorSetPositionSrv.request.value = 0;
158 webots_ros::get_float motorGetTargetPositionSrv;
165 while (!birdCatched &&
ros::ok()) {
166 motorSetPositionSrv.request.value = i;
167 motorSetPositionClient.
call(motorSetPositionSrv);
169 ROS_ERROR(
"Failed to call next step with time_step service.");
172 motorGetTargetPositionClient.
call(motorGetTargetPositionSrv);
184 if (rangeFinderSaveImageClient.
call(rangeFinderSaveImageSrv) && rangeFinderSaveImageSrv.response.success == 1)
185 ROS_INFO(
"What a beautifull bird we found here!");
187 ROS_INFO(
"Failed to call service save_image to take a picture of the bird.");