joystick_modes.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, UC Regents
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 University of California 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 JOYSTICK_MODES_H
00035 #define JOYSTICK_MODES_H
00036 
00037 #include "flyer_controller/control_mode.h"
00038 #include <math.h>
00039 #include <algorithm>
00040 #include <tf/transform_datatypes.h>
00041 
00042 #define DEG2RAD (M_PI/180.0)
00043 #define RAD2DEG (180.0/M_PI)
00044 
00045 using namespace flyer_controller;
00046 using namespace std;
00047 using namespace ControlModeTypes;
00048 using angles::to_degrees;
00049 
00050 namespace flyer_controller
00051 {
00052 
00053 struct joystick_command
00054 {
00055   double roll; // -1..1 (clipped, deadbanded, scaled)
00056   double pitch; // -1..1 (clipped, deadbanded, scaled)
00057   double yaw; // -1..1 (clipped, deadbanded, scaled)
00058   double alt; // -1..1 (clipped, deadbanded, scaled)
00059 };
00060 
00061 // This class is to be used as a base class for modes that use the joystick for input
00062 // (i.e. for more than just altitude and the buttons)
00063 class JoystickMode : public ControlMode
00064 {
00065 protected:
00066   string mode_name_;
00067   // Parameters
00068   double max_yaw_rate_cmd; // [deg/s] yaw rate corresponding to full deflection
00069   double max_alt_cmd; // [m] commanded altitude corresponding to full + deflection
00070   double min_alt_cmd; // [m] commanded altitude corresponding to full - deflection
00071 
00072   // Members
00073 //  joystick_command latest_cmd;
00074 //  double latest_pitch_cmd; // -1..1 (clipped, deadbanded, scaled)
00075 //  double latest_roll_cmd; // -1..1 (clipped, deadbanded, scaled)
00076 //  double latest_yaw_cmd; // -1..1 (clipped, deadbanded, scaled)
00077   double yaw_cmd; // degrees
00078 
00079 public:
00080   JoystickMode(string mode_name) :
00081     mode_name_(mode_name), max_yaw_rate_cmd(10), max_alt_cmd(1.5),
00082         min_alt_cmd(0.0),
00083         //latest_cmd(),
00084         yaw_cmd(0)
00085   {
00086 
00087   }
00088 
00089   void onInit()
00090   {
00091     ControlMode::onInit();
00092     NODELET_WARN("Joystick must be properly calibrated using jscal.. have you done this?");
00093     // Parameters
00094     nh_priv.param("max_yaw_rate_cmd", max_yaw_rate_cmd, max_yaw_rate_cmd);
00095     CHECK_PARAMETER(max_yaw_rate_cmd >= 0, "parameter value out of range");
00096     nh_priv.param("max_alt_cmd", max_alt_cmd, max_alt_cmd);
00097     nh_priv.param("min_alt_cmd", min_alt_cmd, min_alt_cmd);
00098     CHECK_PARAMETER(max_alt_cmd >= min_alt_cmd, "parameter value out of range");
00099 
00100   }
00101 
00102 }; // class
00103 }// namespace
00104 #endif


flyer_controller
Author(s): Patrick Bouffard
autogenerated on Sun Jan 5 2014 11:37:53