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.");
93 else if (getTypeSrv.response.value == 41)
94 ROS_INFO(
"This controller is on a supervisor robot.");
96 ROS_INFO(
"This controller is on a differential wheels robot.");
98 if (getModelClient.
call(getModelSrv)) {
99 if (!getModelSrv.response.value.empty())
100 ROS_INFO(
"The model of this robot is %s.", getModelSrv.response.value.c_str());
102 ROS_ERROR(
"The robot doesn't seems to have a model.");
104 ROS_ERROR(
"Could not get the model of this robot.");
110 n.
serviceClient<webots_ros::robot_get_device_list>(controllerName +
"/robot/get_device_list");
111 webots_ros::robot_get_device_list deviceListSrv;
113 if (deviceListClient.
call(deviceListSrv)) {
114 deviceList = deviceListSrv.response.list;
115 ROS_INFO(
"The controller has %lu devices availables:", deviceList.size());
116 for (
unsigned int i = 0; i < deviceList.size(); i++)
117 ROS_INFO(
"Device [%d]: %s.", i, deviceList[i].c_str());
119 ROS_ERROR(
"Failed to call service deviceList.");
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
static std::string controllerName
uint32_t getNumPublishers() const
ROSCPP_DECL void shutdown()
ROSCPP_DECL void spinOnce()