deliver_message_service.cpp
Go to the documentation of this file.
00001 #include "bwi_services/DeliverMessage.h"
00002 #include "bwi_services/GoToLocation.h"
00003 #include "bwi_services/SpeakMessage.h"
00004 #include <ros/ros.h>
00005 #include <string>
00006 
00007 ros::NodeHandle *n;
00008 
00009 //travels to location and delivers message
00010 
00011 bool deliver_message(bwi_services::DeliverMessage::Request &req,
00012       bwi_services::DeliverMessage::Response &res) {
00013   
00014   ros::ServiceClient goToLocationClient = (*n).serviceClient<bwi_services::GoToLocation>("/bwi_services/go_to_location"); 
00015   bwi_services::GoToLocation goToSrv;
00016   goToSrv.request.location = req.location;
00017   goToLocationClient.call(goToSrv);
00018   ROS_INFO("Location:%s", req.location.c_str());
00019   
00020   //called with header because node is private
00021   ros::ServiceClient speakMessageClient = (*n).serviceClient<bwi_services::SpeakMessage>("/speak_message_service/speak_message");  
00022   bwi_services::SpeakMessage speakSrv;
00023   speakSrv.request.message = req.message;
00024   speakMessageClient.call(speakSrv);  
00025   ROS_INFO("Message:%s", req.message.c_str());
00026   
00027   res.go_to_result = goToSrv.response.result;
00028   res.speak_result = speakSrv.response.result;
00029   
00030   return res.go_to_result == 1 && res.speak_result == 0;
00031 }
00032 
00033 int main(int argc, char** argv) {
00034   //initialize the node
00035   ros::init(argc, argv, "deliver_message_service_node");
00036   ros::NodeHandle nh;
00037   n = &nh;  
00038 
00039   ros::ServiceServer service = (*n).advertiseService("/bwi_services/deliver_message", deliver_message); 
00040   ROS_INFO("DeliverMessage Service started");
00041 
00042   ros::spin();  
00043   ROS_INFO("Done spinning");
00044   return 0;
00045 }
00046 


bwi_services
Author(s): Benjamin Singer
autogenerated on Thu Jun 6 2019 17:57:57