rovio_teleop.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 
00049 #include <geometry_msgs/Twist.h>
00050 #include <ros/ros.h>
00051 #include <rovio_shared/head_ctrl.h>
00052 #include <rovio_ctrl/rovio_teleop.h>
00053 #include <rovio_shared/man_drv.h>
00054 #include <rovio_shared/wav_play.h>
00055 #include <sensor_msgs/Joy.h>
00056 #include <string>
00057 
00058 using namespace std;
00059 
00060 teleop_controller::teleop_controller()
00061 {
00062   // check for all the correct parameters
00063   if (!node.getParam(ROVIO_WAV, rovio_wav))
00064   {
00065     ROS_ERROR("Parameter %s not found.", ROVIO_WAV);
00066     exit(-1);
00067   }
00068 
00069   // create the published topic and client
00070   cmd_vel = node.advertise<geometry_msgs::Twist>("cmd_vel", 10);
00071   head_ctrl = node.serviceClient<rovio_shared::head_ctrl>("head_ctrl");
00072   wav_play = node.serviceClient<rovio_shared::wav_play>("wav_play");
00073 
00074   //subscribe to the joystick
00075   joy_sub = node.subscribe<sensor_msgs::Joy>("joy", 10, &teleop_controller::joy_cback, this);
00076 
00077   ROS_INFO("Rovio Teleop Started");
00078 }
00079 
00080 void teleop_controller::joy_cback(const sensor_msgs::Joy::ConstPtr& joy)
00081 {
00082   // create the message for a speed message and request for the head
00083   rovio_shared::man_drv drv;
00084   rovio_shared::head_ctrl head;
00085   rovio_shared::wav_play wav;
00086 
00087   // check for any head control buttons
00088   head.request.head_pos = -1;
00089   if (joy->buttons.at(0) == 1)
00090     head.request.head_pos = rovio_shared::head_ctrl::Request::HEAD_DOWN;
00091   else if (joy->buttons.at(1) == 1)
00092     head.request.head_pos = rovio_shared::head_ctrl::Request::HEAD_MIDDLE;
00093   else if (joy->buttons.at(2) == 1)
00094     head.request.head_pos = rovio_shared::head_ctrl::Request::HEAD_UP;
00095 
00096   // check if a head request was made
00097   if (head.request.head_pos != -1)
00098     // send the request
00099     head_ctrl.call(head);
00100 
00101   // check for any audio buttons
00102   wav.request.f = "";
00103   wav.request.f.append(rovio_wav);
00104   if (joy->buttons.at(4) == 1)
00105     wav.request.f.append("/G11.wav");
00106   else if (joy->buttons.at(5) == 1)
00107     wav.request.f.append("/G03.wav");
00108   else if (joy->buttons.at(6) == 1)
00109     wav.request.f.append("/G27a.wav");
00110   else if (joy->buttons.at(7) == 1)
00111     wav.request.f.append("/G34.wav");
00112   else
00113     wav.request.f = "";
00114 
00115   // check if a audio request was made
00116   if (wav.request.f.size() > 0)
00117     // send the request
00118     wav_play.call(wav);
00119 
00120   // create the twist message
00121   geometry_msgs::Twist twist;
00122   // left joystick controls the linear movement
00123   twist.linear.x = joy->axes.at(1) * THROTTLE;
00124   twist.linear.y = joy->axes.at(0) * THROTTLE;
00125   twist.linear.z = 0;
00126   // right joystick controls the angular movement
00127   twist.angular.x = 0;
00128   twist.angular.y = 0;
00129   twist.angular.z = joy->axes.at(2) * THROTTLE;
00130   // send the twist command
00131   cmd_vel.publish(twist);
00132 }
00133 
00134 int main(int argc, char **argv)
00135 {
00136   // initialize ROS and the node
00137   ros::init(argc, argv, "rovio_teleop");
00138 
00139   // initialize the Rovio controller
00140   teleop_controller controller;
00141 
00142   // continue until a ctrl-c has occurred
00143   ros::spin();
00144 }


rovio_ctrl
Author(s): Russell Toris
autogenerated on Sat Dec 28 2013 17:38:53