manual_control.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2010, LABUST, UNIZG-FER
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the LABUST nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 #ifndef LABUST_CONTROL_MANUAL_CONTROL_H
00035 #define LABUST_CONTROL_MANUAL_CONTROL_H
00036 
00037 #include <navcon_msgs/ManualConfigure.h>
00038 #include <navcon_msgs/ManualSelect.h>
00039 #include <navcon_msgs/ManualConfiguration.h>
00040 #include <auv_msgs/NavSts.h>
00041 #include <sensor_msgs/Joy.h>
00042 #include <ros/ros.h>
00043 
00044 #include <boost/thread/mutex.hpp>
00045 
00046 #include <string>
00047 #include <map>
00048 
00049 namespace labust
00050 {
00051         namespace control
00052         {
00065                 class ManualControl
00066                 {
00067                         enum {X=0,Y,Z,K,M,N,DOF=6,A=6};
00068 
00069                         typedef boost::array<int,DOF> GenArray;
00070                         typedef std::vector<double> DataType;
00071                         typedef navcon_msgs::ManualConfigure::Request CRequest;
00072                         typedef navcon_msgs::ManualConfigure::Response CResponse;
00073                         typedef navcon_msgs::ManualSelect::Request SRequest;
00074                         typedef navcon_msgs::ManualSelect::Response SResponse;
00075 
00076                 public:
00078                         ManualControl();
00079 
00081                         void onInit();
00082 
00083                 private:
00085                         void onJoystick(const sensor_msgs::Joy::ConstPtr& joy);
00087                         void onNavSts(const auv_msgs::NavSts::ConstPtr& nav);
00089                         bool onConfiguration(CRequest& req, CResponse& resp);
00091                         bool onSelect(SRequest& req, SResponse& resp);
00092 
00094                         bool setupConfig();
00096                         void setDefaultConfig();
00098                         void remap(const sensor_msgs::Joy::ConstPtr& joy);
00100                         void pubTau(const DataType& tauv);
00102                         void pubNu(const DataType& nuv);
00104                         void pubEta(const DataType& etaff);
00105 
00107                         ros::Publisher tauref;
00109                         ros::Publisher nuref;
00111                         ros::Publisher etaref;
00113                         ros::Subscriber joyin;
00115                         ros::Subscriber navsts;
00117                         ros::ServiceServer config_server;
00119                         ros::ServiceServer select_server;
00120 
00122                         navcon_msgs::ManualConfiguration config;
00124                         GenArray generators;
00126                         DataType mapped;
00128                         boost::mutex cfg_mutex;
00129 
00131                         DataType navstate;
00133                         bool nav_valid;
00135                         boost::mutex nav_mutex;
00136                 };
00137         }
00138 }
00139 
00140 /* LABUST_CONTROL_MANUAL_CONTROL_H */
00141 #endif


labust_control
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:22:42