rovio_audio.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2012, Worcester Polytechnic Institute
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Worcester Polytechnic Institute nor the
00019  *     names of its contributors may be used to endorse or promote
00020  *     products derived from this software without specific prior
00021  *     written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  *********************************************************************/
00037 
00048 #include <arpa/inet.h>
00049 #include <cstdlib>
00050 #include <ros/ros.h>
00051 #include <rovio_av/rovio_audio.h>
00052 #include <rovio_shared/rovio_http.h>
00053 #include <rovio_shared/wav_play.h>
00054 #include <string>
00055 #include <sstream>
00056 #include <sys/socket.h>
00057 
00058 using namespace std;
00059 
00060 audio_controller::audio_controller()
00061 {
00062   // check for all the correct parameters
00063   if (!node.getParam(USER, user))
00064   {
00065     ROS_ERROR("Parameter %s not found.", USER);
00066     exit(-1);
00067   }
00068   if (!node.getParam(PASS, pass))
00069   {
00070     ROS_ERROR("Parameter %s not found.", PASS);
00071     exit(-1);
00072   }
00073   if (!node.getParam(HOST, host))
00074   {
00075     ROS_ERROR("Parameter %s not found.", HOST);
00076     exit(-1);
00077   }
00078 
00079   // add services
00080   wav_play = node.advertiseService("wav_play", &audio_controller::wav_play_callback, this);
00081 
00082   ROS_INFO("Rovio Audio Controller Initialized");
00083 }
00084 
00085 bool audio_controller::wav_play_callback(rovio_shared::wav_play::Request &req, rovio_shared::wav_play::Response &resp)
00086 {
00087   // create a socket to talk to the Rovio
00088   int audio_socket = socket(AF_INET, SOCK_STREAM, IPPROTO_TCP);
00089   if (audio_socket < 0)
00090   {
00091     ROS_ERROR("Audio socket could not be created.");
00092     return false;
00093   }
00094 
00095   // setup the address
00096   struct sockaddr_in host_addr;
00097   memset(&host_addr, 0, sizeof(host_addr));
00098   host_addr.sin_family = AF_INET;
00099   host_addr.sin_addr.s_addr = inet_addr(host.c_str());
00100   host_addr.sin_port = htons(80);
00101 
00102   // connect the socket
00103   if (connect(audio_socket, (struct sockaddr *)&host_addr, sizeof(host_addr)) < 0)
00104   {
00105     ROS_ERROR("Audio socket could not be connected.");
00106     return false;
00107   }
00108 
00109   // get the file name from the request
00110   string f_name = req.f;
00111 
00112   // try and open the file
00113   FILE *f = fopen(f_name.c_str(), "rb");
00114   if (f == NULL)
00115   {
00116     ROS_ERROR("Could not open file '%s'.", f_name.c_str());
00117     return false;
00118   }
00119 
00120   // find out how big the file is
00121   fseek(f, 0, SEEK_END);
00122   long f_size = ftell(f);
00123   rewind(f);
00124   // create a buffer and read in the entire file
00125   char *buf = (char*)malloc(f_size);
00126   if ((long)fread(buf, 1, f_size, f) != f_size)
00127   {
00128     ROS_ERROR("Error reading file '%s'.", f_name.c_str());
00129     return false;
00130   }
00131 
00132   // build the header
00133   stringstream ss;
00134   ss << "POST /GetAudio.cgi HTTP/1.1\r\n" << "User-Agent: AudioAgent\r\n" << "Host: " << host << "\r\n"
00135       << "Content-Length: " << f_size << "\r\n" << "Cache-Control: no-cache\r\n" << "\r\n";
00136 
00137   // send the sound file
00138   send(audio_socket, ss.str().c_str(), ss.str().size(), 0);
00139   if (send(audio_socket, buf, f_size, 0) != f_size)
00140   {
00141     ROS_ERROR("Could not send entire file.");
00142     return false;
00143   }
00144 
00145   // close the file
00146   fclose(f);
00147   // free the buffer
00148   free(buf);
00149   // close the socket
00150   close(audio_socket);
00151 
00152   return true;
00153 }
00154 
00155 int main(int argc, char **argv)
00156 {
00157   // initialize ROS and the node
00158   ros::init(argc, argv, "rovio_audio");
00159 
00160   // initialize the Rovio controller
00161   audio_controller controller;
00162 
00163   // update at 5 Hz
00164   ros::Rate loop_rate(5);
00165   // continue until a ctrl-c has occurred
00166   while (ros::ok())
00167   {
00168     ros::spinOnce();
00169     loop_rate.sleep();
00170   }
00171 
00172   return EXIT_SUCCESS;
00173 }


rovio_av
Author(s): Russell Toris
autogenerated on Sat Dec 28 2013 17:38:50