$search
00001 /* 00002 * teleop_base 00003 * Copyright (c) 2008, Willow Garage, Inc. 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions are met: 00008 * 00009 * * Redistributions of source code must retain the above copyright 00010 * notice, this list of conditions and the following disclaimer. 00011 * * Redistributions in binary form must reproduce the above copyright 00012 * notice, this list of conditions and the following disclaimer in the 00013 * documentation and/or other materials provided with the distribution. 00014 * * Neither the name of the <ORGANIZATION> nor the names of its 00015 * contributors may be used to endorse or promote products derived from 00016 * this software without specific prior written permission. 00017 * 00018 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00019 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00020 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00021 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00022 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00023 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00024 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00025 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00026 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00027 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00028 * POSSIBILITY OF SUCH DAMAGE. 00029 */ 00030 00031 /* modifications to teleop_base to work with p2os 00032 * Copyright (C) 2010 David Feil-Seifer [dfseifer@usc.edu], Edward T. Kaszubski [kaszubsk@usc.edu] 00033 * 00034 * This program is free software; you can redistribute it and/or modify 00035 * it under the terms of the GNU General Public License as published by 00036 * the Free Software Foundation; either version 2 of the License, or 00037 * (at your option) any later version. 00038 * 00039 * This program is distributed in the hope that it will be useful, 00040 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00041 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00042 * GNU General Public License for more details. 00043 * 00044 * You should have received a copy of the GNU General Public License 00045 * along with this program; if not, write to the Free Software 00046 * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, 00047 * MA 02110-1301, USA. 00048 */ 00049 00050 00051 #include <cstdlib> 00052 #include <unistd.h> 00053 #include <math.h> 00054 #include "ros/ros.h" 00055 #include "sensor_msgs/Joy.h" 00056 #include "geometry_msgs/Twist.h" 00057 00058 class TeleopBase 00059 { 00060 public: 00061 geometry_msgs::Twist cmd, passthrough_cmd; 00062 double req_vx, req_vy, req_vw; 00063 double max_vx, max_vy, max_vw, max_vx_run, max_vy_run, max_vw_run; 00064 int axis_vx, axis_vy, axis_vw; 00065 int deadman_button, run_button; 00066 bool deadman_no_publish_; 00067 bool deadman_; 00068 bool running_; 00069 00070 ros::Time last_recieved_joy_message_time_; 00071 ros::Duration joy_msg_timeout_; 00072 00073 ros::NodeHandle n_; 00074 ros::Publisher vel_pub_; 00075 ros::Subscriber joy_sub_; 00076 ros::Subscriber passthrough_sub_; 00077 00078 TeleopBase(bool deadman_no_publish = false) : max_vx(0.6), max_vy(0.6), max_vw(0.8), max_vx_run(0.6), max_vy_run(0.6), max_vw_run(0.8), deadman_no_publish_(deadman_no_publish), running_(false), n_( "~" ) 00079 { } 00080 00081 void init() 00082 { 00083 cmd.linear.x = cmd.linear.y = cmd.angular.z = 0; 00084 n_.param("max_vx", max_vx, max_vx); 00085 n_.param("max_vy", max_vy, max_vy); 00086 n_.param("max_vw", max_vw, max_vw); 00087 00088 // Set max speed while running 00089 n_.param("max_vx_run", max_vx_run, max_vx_run); 00090 n_.param("max_vy_run", max_vy_run, max_vy_run); 00091 n_.param("max_vw_run", max_vw_run, max_vw_run); 00092 00093 n_.param("axis_vx", axis_vx, 3); 00094 n_.param("axis_vw", axis_vw, 0); 00095 n_.param("axis_vy", axis_vy, 2); 00096 00097 n_.param("deadman_button", deadman_button, 0); 00098 n_.param("run_button", run_button, 0); 00099 00100 double joy_msg_timeout; 00101 n_.param("joy_msg_timeout", joy_msg_timeout, -1.0); //default to no timeout 00102 if (joy_msg_timeout <= 0) 00103 { 00104 joy_msg_timeout_ = ros::Duration().fromSec(9999999);//DURATION_MAX; 00105 ROS_DEBUG("joy_msg_timeout <= 0 -> no timeout"); 00106 } 00107 else 00108 { 00109 joy_msg_timeout_.fromSec(joy_msg_timeout); 00110 ROS_DEBUG("joy_msg_timeout: %.3f", joy_msg_timeout_.toSec()); 00111 } 00112 00113 ROS_DEBUG("max_vx: %.3f m/s\n", max_vx); 00114 ROS_DEBUG("max_vy: %.3f m/s\n", max_vy); 00115 ROS_DEBUG("max_vw: %.3f deg/s\n", max_vw*180.0/M_PI); 00116 00117 ROS_DEBUG("max_vx_run: %.3f m/s\n", max_vx_run); 00118 ROS_DEBUG("max_vy_run: %.3f m/s\n", max_vy_run); 00119 ROS_DEBUG("max_vw_run: %.3f deg/s\n", max_vw_run*180.0/M_PI); 00120 00121 ROS_DEBUG("axis_vx: %d\n", axis_vx); 00122 ROS_DEBUG("axis_vy: %d\n", axis_vy); 00123 ROS_DEBUG("axis_vw: %d\n", axis_vw); 00124 00125 00126 ROS_INFO("deadman_button: %d", deadman_button); 00127 ROS_INFO("run_button: %d", run_button); 00128 ROS_DEBUG("joy_msg_timeout: %f\n", joy_msg_timeout); 00129 00130 vel_pub_ = n_.advertise<geometry_msgs::Twist>("cmd_vel", 1); 00131 passthrough_sub_ = n_.subscribe( "des_vel", 10, &TeleopBase::passthrough_cb, this ); 00132 joy_sub_ = n_.subscribe("joy", 10, &TeleopBase::joy_cb, this); 00133 00134 00135 } 00136 00137 ~TeleopBase() { } 00138 00139 void passthrough_cb( const geometry_msgs::TwistConstPtr& pass_msg ) 00140 { 00141 ROS_DEBUG( "passthrough_cmd: [%f,%f]", passthrough_cmd.linear.x, passthrough_cmd.angular.z ); 00142 passthrough_cmd = *pass_msg; 00143 } 00144 00145 void joy_cb(const sensor_msgs::Joy::ConstPtr& joy_msg) 00146 { 00147 00148 deadman_ = (((unsigned int)deadman_button < joy_msg->buttons.size()) && joy_msg->buttons[deadman_button]); 00149 00150 if (!deadman_) return; 00151 00152 //Record this message reciept 00153 last_recieved_joy_message_time_ = ros::Time::now(); 00154 00155 // Base 00156 running_ = (((unsigned int)run_button < joy_msg->buttons.size()) && joy_msg->buttons[run_button]); 00157 double vx = running_ ? max_vx_run : max_vx; 00158 double vy = running_ ? max_vy_run : max_vy; 00159 double vw = running_ ? max_vw_run : max_vw; 00160 00161 if((axis_vx >= 0) && (((unsigned int)axis_vx) < joy_msg->axes.size())) 00162 req_vx = joy_msg->axes[axis_vx] * vx; 00163 else 00164 req_vx = 0.0; 00165 if((axis_vy >= 0) && (((unsigned int)axis_vy) < joy_msg->axes.size())) 00166 req_vy = joy_msg->axes[axis_vy] * vy; 00167 else 00168 req_vy = 0.0; 00169 if((axis_vw >= 0) && (((unsigned int)axis_vw) < joy_msg->axes.size())) 00170 req_vw = joy_msg->axes[axis_vw] * vw; 00171 else 00172 req_vw = 0.0; 00173 00174 } 00175 00176 void send_cmd_vel() 00177 { 00178 if(deadman_ && 00179 last_recieved_joy_message_time_ + joy_msg_timeout_ > ros::Time::now() ) 00180 { 00181 if( running_ ) printf( "sprinting!\n" ); 00182 cmd.linear.x = req_vx; 00183 cmd.linear.y = req_vy; 00184 cmd.angular.z = req_vw; 00185 vel_pub_.publish(cmd); 00186 00187 fprintf(stdout,"teleop_base:: %f, %f, %f\n",cmd.linear.x,cmd.linear.y,cmd.angular.z); 00188 } 00189 else 00190 { 00191 //cmd.linear.x = cmd.linear.y = cmd.angular.z = 0; 00192 cmd = passthrough_cmd; 00193 //if (!deadman_no_publish_) 00194 { 00195 vel_pub_.publish(cmd);//Only publish if deadman_no_publish is enabled 00196 00197 } 00198 } 00199 } 00200 }; 00201 00202 int main(int argc, char **argv) 00203 { 00204 ros::init(argc, argv, "teleop_base"); 00205 const char* opt_no_publish = "--deadman_no_publish"; 00206 00207 bool no_publish = false; 00208 for(int i=1;i<argc;i++) 00209 { 00210 if(!strncmp(argv[i], opt_no_publish, strlen(opt_no_publish))) 00211 no_publish = true; 00212 } 00213 00214 TeleopBase teleop_base(no_publish); 00215 00216 ros::Rate pub_rate(20); 00217 00218 teleop_base.init(); 00219 00220 while (ros::ok()) 00221 { 00222 ros::spinOnce(); 00223 teleop_base.send_cmd_vel(); 00224 pub_rate.sleep(); 00225 } 00226 00227 exit(0); 00228 return 0; 00229 }