22 #include <webots_ros/robot_get_device_list.h>
24 #include <webots_ros/get_int.h>
25 #include <webots_ros/get_string.h>
29 #include <std_msgs/String.h>
44 ROS_INFO(
"User stopped the 'robot_information_parser' node.");
49 int main(
int argc,
char **argv) {
51 std::vector<std::string> deviceList;
71 int wantedController = 0;
72 std::cout <<
"Choose the # of the controller you want to use:\n";
73 std::cin >> wantedController;
77 ROS_ERROR(
"Invalid number for controller choice.");
86 webots_ros::get_int getTypeSrv;
88 webots_ros::get_string getModelSrv;
90 getTypeClient.
call(getTypeSrv);
91 if (getTypeSrv.response.value == 40)
92 ROS_INFO(
"This controller is on a basic robot.");
94 ROS_INFO(
"This controller is on a supervisor robot.");
96 if (getModelClient.
call(getModelSrv)) {
97 if (!getModelSrv.response.value.empty())
98 ROS_INFO(
"The model of this robot is %s.", getModelSrv.response.value.c_str());
100 ROS_ERROR(
"The robot doesn't seems to have a model.");
102 ROS_ERROR(
"Could not get the model of this robot.");
109 webots_ros::robot_get_device_list deviceListSrv;
111 if (deviceListClient.
call(deviceListSrv)) {
112 deviceList = deviceListSrv.response.list;
113 ROS_INFO(
"The controller has %lu devices availables:", deviceList.size());
114 for (
unsigned int i = 0; i < deviceList.size(); i++)
115 ROS_INFO(
"Device [%d]: %s.", i, deviceList[i].c_str());
117 ROS_ERROR(
"Failed to call service deviceList.");