JoystickDemo.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2018-2019, Dataspeed Inc.
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 Dataspeed Inc. 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 
00035 #include "JoystickDemo.h"
00036 
00037 JoystickDemo::JoystickDemo(ros::NodeHandle &node, ros::NodeHandle &priv_nh) : counter_(0)
00038 {
00039   joy_.axes.resize(AXIS_COUNT_X, 0);
00040   joy_.buttons.resize(BTN_COUNT_X, 0);
00041 
00042   brake_ = true;
00043   throttle_ = true;
00044   steer_ = true;
00045   shift_ = true;
00046   signal_ = true;
00047   priv_nh.getParam("brake", brake_);
00048   priv_nh.getParam("throttle", throttle_);
00049   priv_nh.getParam("steer", steer_);
00050   priv_nh.getParam("shift", shift_);
00051   priv_nh.getParam("signal", signal_);
00052 
00053   brake_gain_ = 1.0;
00054   throttle_gain_ = 1.0;
00055   priv_nh.getParam("brake_gain", brake_gain_);
00056   priv_nh.getParam("throttle_gain", throttle_gain_);
00057   brake_gain_    = std::min(std::max(brake_gain_,    (float)0), (float)1);
00058   throttle_gain_ = std::min(std::max(throttle_gain_, (float)0), (float)1);
00059 
00060   ignore_ = false;
00061   enable_ = true;
00062   count_ = false;
00063   strq_ = false;
00064   svel_ = 0.0;
00065   last_steering_filt_output_ = 0.0;
00066   priv_nh.getParam("ignore", ignore_);
00067   priv_nh.getParam("enable", enable_);
00068   priv_nh.getParam("count", count_);
00069   priv_nh.getParam("strq", strq_);
00070   priv_nh.getParam("svel", svel_);
00071 
00072   sub_joy_ = node.subscribe("/joy", 1, &JoystickDemo::recvJoy, this);
00073 
00074   data_.brake_joy = 0.0;
00075   data_.gear_cmd = dbw_fca_msgs::Gear::NONE;
00076   data_.steering_joy = 0.0;
00077   data_.steering_mult = false;
00078   data_.throttle_joy = 0.0;
00079   data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::NONE;
00080   data_.joy_throttle_valid = false;
00081   data_.joy_brake_valid = false;
00082 
00083   if (brake_) {
00084     pub_brake_ = node.advertise<dbw_fca_msgs::BrakeCmd>("brake_cmd", 1);
00085   }
00086   if (throttle_) {
00087     pub_throttle_ = node.advertise<dbw_fca_msgs::ThrottleCmd>("throttle_cmd", 1);
00088   }
00089   if (steer_) {
00090     pub_steering_ = node.advertise<dbw_fca_msgs::SteeringCmd>("steering_cmd", 1);
00091   }
00092   if (shift_) {
00093     pub_gear_ = node.advertise<dbw_fca_msgs::GearCmd>("gear_cmd", 1);
00094   }
00095   if (signal_) {
00096     pub_turn_signal_ = node.advertise<dbw_fca_msgs::TurnSignalCmd>("turn_signal_cmd", 1);
00097   }
00098   if (enable_) {
00099     pub_enable_ = node.advertise<std_msgs::Empty>("enable", 1);
00100     pub_disable_ = node.advertise<std_msgs::Empty>("disable", 1);
00101   }
00102 
00103   timer_ = node.createTimer(ros::Duration(0.02), &JoystickDemo::cmdCallback, this);
00104 }
00105 
00106 void JoystickDemo::cmdCallback(const ros::TimerEvent& event)
00107 {
00108   // Detect joy timeouts and reset
00109   if (event.current_real - data_.stamp > ros::Duration(0.1)) {
00110     data_.joy_throttle_valid = false;
00111     data_.joy_brake_valid = false;
00112     last_steering_filt_output_ = 0.0;
00113     return;
00114   }
00115 
00116   // Optional watchdog counter
00117   if (count_) {
00118     counter_++;
00119   }
00120 
00121   // Brake
00122   if (brake_) {
00123     dbw_fca_msgs::BrakeCmd msg;
00124     msg.enable = true;
00125     msg.ignore = ignore_;
00126     msg.count = counter_;
00127     msg.pedal_cmd_type = dbw_fca_msgs::BrakeCmd::CMD_PERCENT;
00128     msg.pedal_cmd = data_.brake_joy * brake_gain_;
00129     pub_brake_.publish(msg);
00130   }
00131 
00132   // Throttle
00133   if (throttle_) {
00134     dbw_fca_msgs::ThrottleCmd msg;
00135     msg.enable = true;
00136     msg.ignore = ignore_;
00137     msg.count = counter_;
00138     msg.pedal_cmd_type = dbw_fca_msgs::ThrottleCmd::CMD_PERCENT;
00139     msg.pedal_cmd = data_.throttle_joy * throttle_gain_;
00140     pub_throttle_.publish(msg);
00141   }
00142 
00143   // Steering
00144   if (steer_) {
00145     dbw_fca_msgs::SteeringCmd msg;
00146     msg.enable = true;
00147     msg.ignore = ignore_;
00148     msg.count = counter_;
00149     if (!strq_) {
00150       msg.cmd_type = dbw_fca_msgs::SteeringCmd::CMD_ANGLE;
00151 
00152       float raw_steering_cmd;
00153       if (data_.steering_mult) {
00154         raw_steering_cmd = dbw_fca_msgs::SteeringCmd::ANGLE_MAX * data_.steering_joy;
00155       } else {
00156         raw_steering_cmd = 0.5 * dbw_fca_msgs::SteeringCmd::ANGLE_MAX * data_.steering_joy;
00157       }
00158 
00159       float tau = 0.1;
00160       float filtered_steering_cmd = 0.02 / tau * raw_steering_cmd + (1 - 0.02 / tau) * last_steering_filt_output_;
00161       last_steering_filt_output_ = filtered_steering_cmd;
00162 
00163       msg.steering_wheel_angle_velocity = svel_;
00164       msg.steering_wheel_angle_cmd = filtered_steering_cmd;
00165     } else {
00166       msg.cmd_type = dbw_fca_msgs::SteeringCmd::CMD_TORQUE;
00167       msg.steering_wheel_torque_cmd = dbw_fca_msgs::SteeringCmd::TORQUE_MAX * data_.steering_joy;
00168     }
00169     pub_steering_.publish(msg);
00170   }
00171 
00172   // Gear
00173   if (shift_) {
00174     if (data_.gear_cmd != dbw_fca_msgs::Gear::NONE) {
00175       dbw_fca_msgs::GearCmd msg;
00176       msg.cmd.gear = data_.gear_cmd;
00177       pub_gear_.publish(msg);
00178     }
00179   }
00180 
00181   // Turn signal
00182   if (signal_) {
00183     dbw_fca_msgs::TurnSignalCmd msg;
00184     msg.cmd.value = data_.turn_signal_cmd;
00185     pub_turn_signal_.publish(msg);
00186   }
00187 }
00188 
00189 void JoystickDemo::recvJoy(const sensor_msgs::Joy::ConstPtr& msg)
00190 {
00191   // Check for expected sizes
00192   if (msg->axes.size() != (size_t)AXIS_COUNT_X && msg->buttons.size() != (size_t)BTN_COUNT_X) {
00193     if (msg->axes.size() == (size_t)AXIS_COUNT_D && msg->buttons.size() == (size_t)BTN_COUNT_D) {
00194       ROS_ERROR_THROTTLE(2.0, "Detected Logitech Gamepad F310 in DirectInput (D) mode. Please select (X) with the switch on the back to select XInput mode.");
00195     }
00196     if (msg->axes.size() != (size_t)AXIS_COUNT_X) {
00197       ROS_ERROR_THROTTLE(2.0, "Expected %zu joy axis count, received %zu", (size_t)AXIS_COUNT_X, msg->axes.size());
00198     }
00199     if (msg->buttons.size() != (size_t)BTN_COUNT_X) {
00200       ROS_ERROR_THROTTLE(2.0, "Expected %zu joy button count, received %zu", (size_t)BTN_COUNT_X, msg->buttons.size());
00201     }
00202     return;
00203   }
00204 
00205   // Handle joystick startup
00206   if (msg->axes[AXIS_THROTTLE] != 0.0) {
00207     data_.joy_throttle_valid = true;
00208   }
00209   if (msg->axes[AXIS_BRAKE] != 0.0) {
00210     data_.joy_brake_valid = true;
00211   }
00212 
00213   // Throttle
00214   if (data_.joy_throttle_valid) {
00215     data_.throttle_joy = 0.5 - 0.5 * msg->axes[AXIS_THROTTLE];
00216   }
00217 
00218   // Brake
00219   if (data_.joy_brake_valid) {
00220     data_.brake_joy = 0.5 - 0.5 * msg->axes[AXIS_BRAKE];
00221   }
00222 
00223   // Gear
00224   if (msg->buttons[BTN_PARK]) {
00225     data_.gear_cmd = dbw_fca_msgs::Gear::PARK;
00226   } else if (msg->buttons[BTN_REVERSE]) {
00227     data_.gear_cmd = dbw_fca_msgs::Gear::REVERSE;
00228   } else if (msg->buttons[BTN_DRIVE]) {
00229     data_.gear_cmd = dbw_fca_msgs::Gear::DRIVE;
00230   } else if (msg->buttons[BTN_NEUTRAL]) {
00231     data_.gear_cmd = dbw_fca_msgs::Gear::NEUTRAL;
00232   } else {
00233     data_.gear_cmd = dbw_fca_msgs::Gear::NONE;
00234   }
00235 
00236   // Steering
00237   data_.steering_joy = (fabs(msg->axes[AXIS_STEER_1]) > fabs(msg->axes[AXIS_STEER_2])) ? msg->axes[AXIS_STEER_1] : msg->axes[AXIS_STEER_2];
00238   data_.steering_mult = msg->buttons[BTN_STEER_MULT_1] || msg->buttons[BTN_STEER_MULT_2];
00239 
00240   // Turn signal
00241   if (msg->axes[AXIS_TURN_SIG] != joy_.axes[AXIS_TURN_SIG]) {
00242     switch (data_.turn_signal_cmd) {
00243       case dbw_fca_msgs::TurnSignal::NONE:
00244         if (msg->axes[AXIS_TURN_SIG] < -0.5) {
00245           data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::RIGHT;
00246         } else if (msg->axes[AXIS_TURN_SIG] > 0.5) {
00247           data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::LEFT;
00248         }
00249         break;
00250       case dbw_fca_msgs::TurnSignal::LEFT:
00251         if (msg->axes[AXIS_TURN_SIG] < -0.5) {
00252           data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::RIGHT;
00253         } else if (msg->axes[AXIS_TURN_SIG] > 0.5) {
00254           data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::NONE;
00255         }
00256         break;
00257       case dbw_fca_msgs::TurnSignal::RIGHT:
00258         if (msg->axes[AXIS_TURN_SIG] < -0.5) {
00259           data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::NONE;
00260         } else if (msg->axes[AXIS_TURN_SIG] > 0.5) {
00261           data_.turn_signal_cmd = dbw_fca_msgs::TurnSignal::LEFT;
00262         }
00263         break;
00264     }
00265   }
00266 
00267   // Optional enable and disable buttons
00268   if (enable_) {
00269     const std_msgs::Empty empty;
00270     if (msg->buttons[BTN_ENABLE]) {
00271       pub_enable_.publish(empty);
00272     }
00273     if (msg->buttons[BTN_DISABLE]) {
00274       pub_disable_.publish(empty);
00275     }
00276   }
00277 
00278   data_.stamp = ros::Time::now();
00279   joy_ = *msg;
00280 }
00281 


dbw_fca_joystick_demo
Author(s): Micho Radovnikovich
autogenerated on Sat May 4 2019 02:40:34