rb1_base_pad.cpp
Go to the documentation of this file.
00001 /*
00002  * rb1_base_pad
00003  * Copyright (c) 2012, Robotnik Automation, SLL
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 Robotnik Automation, SLL. 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  * \author Robotnik Automation, SLL
00031  * \brief Allows to use a pad with the roboy controller, sending the messages received from the joystick device
00032  */
00033 
00034 
00035 #include <ros/ros.h>
00036 #include <sensor_msgs/Joy.h>
00037 #include <geometry_msgs/Twist.h>
00038 #include <robotnik_msgs/ptz.h>
00039 // Not yet catkinized 9/2013
00040 // #include <sound_play/sound_play.h>
00041 #include <unistd.h>
00042 #include <robotnik_msgs/set_mode.h>
00043 #include <rb1_base_pad/enable_disable_pad.h>
00044 #include <robotnik_msgs/set_digital_output.h>
00045 #include <robotnik_msgs/ptz.h>
00046 #include <robotnik_msgs/home.h>
00047 #include <diagnostic_updater/diagnostic_updater.h>
00048 #include <diagnostic_updater/publisher.h>
00049 #include <rb1_base_msgs/SetElevator.h>
00050 
00051 #define DEFAULT_NUM_OF_BUTTONS          16
00052 #define DEFAULT_AXIS_LINEAR_X           1
00053 #define DEFAULT_AXIS_LINEAR_Y       0
00054 #define DEFAULT_AXIS_ANGULAR            2
00055 #define DEFAULT_AXIS_LINEAR_Z       3   
00056 #define DEFAULT_SCALE_LINEAR            1.0
00057 #define DEFAULT_SCALE_ANGULAR           2.0
00058 #define DEFAULT_SCALE_LINEAR_Z      1.0 
00059 
00060 #define ITERATIONS_AFTER_DEADMAN    3.0
00061     
00062 #define DEFAULT_ELEVATOR_ACTION_RAISE   1 
00063 #define DEFAULT_ELEVATOR_ACTION_LOWER   -1 
00064 #define DEFAULT_ELEVATOR_ACTION_STOP    0 
00065 #define JOY_ERROR_TIME                                  1.0
00066 
00067 //                               NOTE:                                //
00068 // This configuration is made for a THRUSTMASTER T-Wireless 3in1 Joy  //
00069 //   please feel free to modify to adapt for your own joystick.       //   
00070 //                                                                    //
00071 
00072 
00073 class RB1BasePad
00074 {
00075         public:
00076         RB1BasePad();
00077         void Update();
00078 
00079         private:
00080         void padCallback(const sensor_msgs::Joy::ConstPtr& joy);
00081         bool EnableDisablePad(rb1_base_pad::enable_disable_pad::Request &req, rb1_base_pad::enable_disable_pad::Response &res );
00082 
00083         ros::NodeHandle nh_;
00084 
00085         int linear_x_, linear_y_, linear_z_, angular_;
00086         double l_scale_, a_scale_, l_scale_z_; 
00088         ros::Publisher vel_pub_, ptz_pub_;
00090         ros::Subscriber pad_sub_;
00092         std::string cmd_topic_vel_;
00094         std::string cmd_service_io_;
00096         std::string elevator_service_name_;
00098         std::string cmd_topic_ptz_;
00099         double current_vel;
00101         int dead_man_button_;
00103         int speed_up_button_, speed_down_button_;
00104         int button_output_1_, button_output_2_;
00105         int button_raise_elevator_, button_lower_elevator_, button_stop_elevator_;
00106         int output_1_, output_2_;
00107         bool bOutput1, bOutput2;
00109         int button_kinematic_mode_;
00111         int kinematic_mode_;
00113         ros::ServiceClient setKinematicMode;  
00115         std::string cmd_set_mode_;
00117         int button_home_;
00119         ros::ServiceClient doHome;
00121         std::string cmd_home_;
00123         int ptz_tilt_up_, ptz_tilt_down_, ptz_pan_right_, ptz_pan_left_;
00125         // ros::ServiceServer enable_disable_srv_;
00126 
00128         ros::ServiceClient set_digital_outputs_client_;  
00130         ros::ServiceClient set_elevator_client_;  
00132         int num_of_buttons_;
00134         bool bRegisteredButtonEvent[DEFAULT_NUM_OF_BUTTONS];
00135         // DIAGNOSTICS
00137         diagnostic_updater::HeaderlessTopicDiagnostic *pub_command_freq; 
00139         diagnostic_updater::HeaderlessTopicDiagnostic *sus_joy_freq; 
00141         diagnostic_updater::Updater updater_pad;        
00143         double min_freq_command, min_freq_joy; // 
00145         double max_freq_command, max_freq_joy; //       
00147         // bool bEnable;
00149     //  sound_play::SoundClient sc;
00151         int pan_increment_, tilt_increment_;
00152 };
00153 
00154 
00155 RB1BasePad::RB1BasePad():
00156   linear_x_(1),
00157   linear_y_(0),
00158   angular_(2),
00159   linear_z_(3)
00160 {
00161         current_vel = 0.1;
00162         // 
00163         nh_.param("num_of_buttons", num_of_buttons_, DEFAULT_NUM_OF_BUTTONS);
00164 
00165     // MOTION CONF
00166         nh_.param("axis_linear_x", linear_x_, DEFAULT_AXIS_LINEAR_X);
00167     nh_.param("axis_linear_y", linear_y_, DEFAULT_AXIS_LINEAR_Y);
00168         nh_.param("axis_linear_z", linear_z_, DEFAULT_AXIS_LINEAR_Z);
00169         nh_.param("axis_angular", angular_, DEFAULT_AXIS_ANGULAR);
00170         nh_.param("scale_angular", a_scale_, DEFAULT_SCALE_ANGULAR);
00171         nh_.param("scale_linear", l_scale_, DEFAULT_SCALE_LINEAR);
00172         nh_.param("scale_linear_z", l_scale_z_, DEFAULT_SCALE_LINEAR_Z);
00173         nh_.param("cmd_topic_vel", cmd_topic_vel_, cmd_topic_vel_);
00174         nh_.param("button_dead_man", dead_man_button_, dead_man_button_);
00175         nh_.param("button_speed_up", speed_up_button_, speed_up_button_);  //4 Thrustmaster
00176         nh_.param("button_speed_down", speed_down_button_, speed_down_button_); //5 Thrustmaster
00177         
00178         // DIGITAL OUTPUTS CONF
00179         nh_.param("cmd_service_io", cmd_service_io_, cmd_service_io_);
00180         nh_.param("button_output_1", button_output_1_, button_output_1_);
00181         nh_.param("button_output_2", button_output_2_, button_output_2_);
00182         nh_.param("output_1", output_1_, output_1_);
00183         nh_.param("output_2", output_2_, output_2_);
00184     // PANTILT CONF
00185         nh_.param("cmd_topic_ptz", cmd_topic_ptz_, cmd_topic_ptz_);
00186         nh_.param("button_ptz_tilt_up", ptz_tilt_up_, ptz_tilt_up_);
00187         nh_.param("button_ptz_tilt_down", ptz_tilt_down_, ptz_tilt_down_);
00188         nh_.param("button_ptz_pan_right", ptz_pan_right_, ptz_pan_right_);
00189         nh_.param("button_ptz_pan_left", ptz_pan_left_, ptz_pan_left_);
00190     nh_.param("button_home", button_home_, button_home_);
00191         nh_.param("pan_increment", pan_increment_, 1);
00192         nh_.param("tilt_increment",tilt_increment_, 1);
00193         nh_.param("button_lower_elevator",button_lower_elevator_, 6);
00194         nh_.param("button_raise_elevator",button_raise_elevator_, 4);
00195         nh_.param("button_stop_elevator",button_stop_elevator_, 16);
00196 
00197     nh_.param("cmd_service_home", cmd_home_, cmd_home_);
00198     nh_.param<std::string>("elevator_service_name", elevator_service_name_, "/rb1_base_controller/set_elevation");
00199         
00200         ROS_INFO("RB1BasePad num_of_buttons_ = %d", num_of_buttons_);   
00201         for(int i = 0; i < num_of_buttons_; i++){
00202                 bRegisteredButtonEvent[i] = false;
00203                 ROS_INFO("bREG %d", i);
00204                 }
00205 
00206         // Publish through the node handle Twist type messages to the guardian_controller/command topic
00207         vel_pub_ = nh_.advertise<geometry_msgs::Twist>(cmd_topic_vel_, 1);
00208         //  Publishes msgs for the pant-tilt cam
00209     ptz_pub_ = nh_.advertise<robotnik_msgs::ptz>(cmd_topic_ptz_, 1);
00210 
00211         // Listen through the node handle sensor_msgs::Joy messages from joystick 
00212     // (these are the references that we will sent to cmd_vel)
00213         pad_sub_ = nh_.subscribe<sensor_msgs::Joy>("joy", 10, &RB1BasePad::padCallback, this);
00214         
00215         // Request service to activate / deactivate digital I/O
00216         set_digital_outputs_client_ = nh_.serviceClient<robotnik_msgs::set_digital_output>(cmd_service_io_);
00217         set_elevator_client_ = nh_.serviceClient<rb1_base_msgs::SetElevator>(elevator_service_name_);
00218         
00219         bOutput1 = bOutput2 = false;
00220 
00221     // Request service to start homing
00222         doHome = nh_.serviceClient<robotnik_msgs::home>(cmd_home_);
00223 
00224         // Diagnostics
00225         updater_pad.setHardwareID("None");
00226         // Topics freq control 
00227         min_freq_command = min_freq_joy = 5.0;
00228         max_freq_command = max_freq_joy = 50.0;
00229         sus_joy_freq = new diagnostic_updater::HeaderlessTopicDiagnostic("/joy", updater_pad,
00230                             diagnostic_updater::FrequencyStatusParam(&min_freq_joy, &max_freq_joy, 0.1, 10));
00231 
00232         pub_command_freq = new diagnostic_updater::HeaderlessTopicDiagnostic(cmd_topic_vel_.c_str(), updater_pad,
00233                             diagnostic_updater::FrequencyStatusParam(&min_freq_command, &max_freq_command, 0.1, 10));
00234 
00235         // Advertises new service to enable/disable the pad
00236         // enable_disable_srv_ = nh_.advertiseService("/rb1_base_pad/enable_disable_pad",  &RB1BasePad::EnableDisablePad, this);
00237         // bEnable = true;      // Communication flag enabled by default
00238 
00239 }
00240 
00241 
00242 /*
00243  *      \brief Updates the diagnostic component. Diagnostics
00244  *
00245  */
00246 void RB1BasePad::Update(){
00247         updater_pad.update();
00248 }
00249 
00250 /*
00251  *      \brief Enables/Disables the pad
00252  *
00253  */
00254 /*
00255 bool RB1BasePad::EnableDisablePad(rb1_base_pad::enable_disable_pad::Request &req, rb1_base_pad::enable_disable_pad::Response &res )
00256 {
00257         bEnable = req.value;
00258 
00259         ROS_INFO("RB1BasePad::EnablaDisablePad: Setting to %d", req.value);
00260         res.ret = true;
00261         return true;
00262 }
00263 */
00264 
00265 void RB1BasePad::padCallback(const sensor_msgs::Joy::ConstPtr& joy)
00266 {
00267         geometry_msgs::Twist vel;
00268         robotnik_msgs::ptz ptz;
00269         bool ptzEvent = false;
00270         static int send_iterations_after_dead_man = 0;
00271         
00272         // Checks the ROS time to avoid noise in the pad
00273         if((ros::Time::now() - joy->header.stamp).toSec() > JOY_ERROR_TIME)
00274                 return;
00275 
00276         vel.angular.x = 0.0;  vel.angular.y = 0.0; vel.angular.z = 0.0;
00277         vel.linear.x = 0.0;   vel.linear.y = 0.0; vel.linear.z = 0.0;
00278 
00279         // Actions dependant on dead-man button
00280         if (joy->buttons[dead_man_button_] == 1) {
00281                 //ROS_ERROR("RB1BasePad::padCallback: DEADMAN button %d", dead_man_button_);
00282                 // Set the current velocity level
00283                 if ( joy->buttons[speed_down_button_] == 1 ){
00284 
00285                         if(!bRegisteredButtonEvent[speed_down_button_]) 
00286                                 if(current_vel > 0.1){
00287                                         current_vel = current_vel - 0.1;
00288                                         bRegisteredButtonEvent[speed_down_button_] = true;
00289                                         ROS_INFO("Velocity: %f%%", current_vel*100.0);  
00290                                         char buf[50]="\0";
00291                                         int percent = (int) (current_vel*100.0);
00292                                         sprintf(buf," %d percent", percent);
00293                     // sc.say(buf);
00294                                 }               
00295                 }else{
00296                         bRegisteredButtonEvent[speed_down_button_] = false;
00297                  }
00298                  
00299                 if (joy->buttons[speed_up_button_] == 1){
00300                         if(!bRegisteredButtonEvent[speed_up_button_])
00301                                 if(current_vel < 0.9){
00302                                         current_vel = current_vel + 0.1;
00303                                         bRegisteredButtonEvent[speed_up_button_] = true;
00304                                         ROS_INFO("Velocity: %f%%", current_vel*100.0);
00305                                         char buf[50]="\0";
00306                                         int percent = (int) (current_vel*100.0);
00307                                         sprintf(buf," %d percent", percent);
00308                     // sc.say(buf);
00309                                 }
00310                   
00311                 }else{
00312                         bRegisteredButtonEvent[speed_up_button_] = false;
00313                 }
00314                  
00315                 vel.angular.x = current_vel*(a_scale_*joy->axes[angular_]);
00316                 vel.angular.y = current_vel*(a_scale_*joy->axes[angular_]);
00317                 vel.angular.z = current_vel*(a_scale_*joy->axes[angular_]);
00318                 vel.linear.x = current_vel*l_scale_*joy->axes[linear_x_];
00319                 vel.linear.y = current_vel*l_scale_*joy->axes[linear_y_];
00320                 vel.linear.z = current_vel*l_scale_z_*joy->axes[linear_z_];
00321 
00322                 // ELEVATOR
00323                 if (joy->buttons[button_stop_elevator_] == 1) {
00324 
00325                         if(!bRegisteredButtonEvent[button_stop_elevator_]){
00326                                 //ROS_INFO("RB1BasePad::padCallback: button %d", button_stop_elevator_);
00327                                 rb1_base_msgs::SetElevator elevator_msg_srv;
00328                                 
00329                                 elevator_msg_srv.request.action = DEFAULT_ELEVATOR_ACTION_STOP;
00330                                 
00331                                 set_elevator_client_.call( elevator_msg_srv );
00332                                 bRegisteredButtonEvent[button_stop_elevator_] = true;
00333                         }
00334                 }else{
00335                         bRegisteredButtonEvent[button_stop_elevator_] = false;
00336                 }
00337                 if (joy->buttons[button_raise_elevator_] == 1) {
00338 
00339                         if(!bRegisteredButtonEvent[button_raise_elevator_]){
00340                                 //ROS_INFO("RB1BasePad::padCallback: button %d", button_raise_elevator_);
00341                                 rb1_base_msgs::SetElevator elevator_msg_srv;
00342                                 
00343                                 elevator_msg_srv.request.action = DEFAULT_ELEVATOR_ACTION_RAISE;
00344                                 
00345                                 set_elevator_client_.call( elevator_msg_srv );
00346                                 bRegisteredButtonEvent[button_raise_elevator_] = true;
00347                         }
00348                 }else{
00349                         bRegisteredButtonEvent[button_raise_elevator_] = false;
00350                 }
00351                 if (joy->buttons[button_lower_elevator_] == 1) {
00352 
00353                         if(!bRegisteredButtonEvent[button_lower_elevator_]){
00354                                 //ROS_INFO("RB1BasePad::padCallback: button %d", button_lower_elevator_);
00355                                 rb1_base_msgs::SetElevator elevator_msg_srv;
00356                                 
00357                                 elevator_msg_srv.request.action = DEFAULT_ELEVATOR_ACTION_LOWER;
00358                                 
00359                                 set_elevator_client_.call( elevator_msg_srv );
00360                                 bRegisteredButtonEvent[button_lower_elevator_] = true;
00361                         }
00362                 }else{
00363                         bRegisteredButtonEvent[button_lower_elevator_] = false;
00364                 }       
00365 
00366         }
00367         else {
00368                 vel.angular.x = 0.0;    vel.angular.y = 0.0; vel.angular.z = 0.0;
00369                 vel.linear.x = 0.0; vel.linear.y = 0.0; vel.linear.z = 0.0;
00370         }
00371 
00372         sus_joy_freq->tick();   // Ticks the reception of joy events
00373 
00374         // Publish only with deadman button pushed for twist use
00375         if (joy->buttons[dead_man_button_] == 1) {
00376                 send_iterations_after_dead_man = ITERATIONS_AFTER_DEADMAN;             
00377                 if (ptzEvent) ptz_pub_.publish(ptz);
00378                 vel_pub_.publish(vel);
00379                 pub_command_freq->tick();
00380                 }
00381         else { // send some 0 if deadman is released
00382           if (send_iterations_after_dead_man >0) {
00383                 send_iterations_after_dead_man--;
00384                 vel_pub_.publish(vel);
00385                 pub_command_freq->tick(); 
00386                 }
00387              }
00388 }
00389 
00390 
00391 int main(int argc, char** argv)
00392 {
00393         ros::init(argc, argv, "rb1_base_pad");
00394         RB1BasePad rb1_base_pad;
00395 
00396         ros::Rate r(50.0);
00397 
00398         while( ros::ok() ){
00399                 // UPDATING DIAGNOSTICS
00400                 rb1_base_pad.Update();
00401                 ros::spinOnce();
00402                 r.sleep();
00403                 }
00404 }
00405 


rb1_base_pad
Author(s): Roberto Guzmán
autogenerated on Sat Jun 8 2019 20:41:48