agvs_pad_node.cpp
Go to the documentation of this file.
00001 /*
00002  * agvs_pad
00003  * Copyright (c) 2013, 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 robot 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 <std_msgs/Int32.h>
00039 #include <unistd.h>
00040 #include <vector>
00041 #include <robotnik_msgs/enable_disable.h>
00042 #include <robotnik_msgs/set_digital_output.h>
00043 #include "diagnostic_msgs/DiagnosticStatus.h"
00044 #include "diagnostic_updater/diagnostic_updater.h"
00045 #include "diagnostic_updater/update_functions.h"
00046 #include "diagnostic_updater/DiagnosticStatusWrapper.h"
00047 #include "diagnostic_updater/publisher.h"
00048 // #include <agvs_controller/AckermannDriveStamped.h>
00049 //#include <agvs_robot_control/AckermannDriveStamped.h>
00050 #include "ackermann_msgs/AckermannDriveStamped.h"
00051 #include <std_srvs/Empty.h>
00052 
00053 #define DEFAULT_MAX_SKID_LINEAR_SPEED   2.0 //m/s
00054 #define DEFAULT_MAX_ANGULAR_POSITION    2.0 // rads/s
00055 
00056 #define MAX_NUM_OF_BUTTONS                      16
00057 #define MAX_NUM_OF_AXES                         8
00058 #define MAX_NUM_OF_BUTTONS_PS3          19
00059 #define MAX_NUM_OF_AXES_PS3                     20
00060 
00061 #define DEFAULT_NUM_OF_BUTTONS          16
00062 #define DEFAULT_NUM_OF_AXES                     8
00063 
00064 #define DEFAULT_AXIS_LINEAR_X           1
00065 #define DEFAULT_AXIS_ANGULAR            0       
00066 #define DEFAULT_SCALE_LINEAR            1.0
00067 #define DEFAULT_SCALE_ANGULAR           1.0
00068 
00069 
00070 #define DEFAULT_JOY                     "/joy"
00071 
00072 #define DEFAULT_HZ                      50.0
00073 
00075 class Button{
00076         int iPressed;
00077         bool bReleased;
00078         
00079         public:
00080         
00081         Button(){
00082                 iPressed = 0;
00083                 bReleased = false;
00084         }
00086         void Press(int value){          
00087                 if(iPressed and !value){
00088                         bReleased = true;
00089                         
00090                 }else if(bReleased and value)
00091                         bReleased = false;
00092                         
00093                 iPressed = value;
00094                         
00095         }
00096         
00097         int IsPressed(){
00098                 return iPressed;
00099         }
00100         
00101         bool IsReleased(){
00102                 bool b = bReleased;
00103                 bReleased = false;
00104                 return b;
00105         }
00106 };
00107 
00109 //                                                                              //
00111 class AgvsPad
00112 {
00113         public:
00114         
00115         AgvsPad();
00116         
00117         void ControlLoop();
00118         int SetStateMode(int state, int arm_mode, int platform_mode);
00119         
00120         private:
00121         
00122         void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
00123         
00124         char * StateToString(int state);
00125         int SwitchToState(int new_state);
00126         
00127         void PublishState();
00129         bool EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res );
00130         void Update();
00131         
00132 private:        
00133         
00134         ros::NodeHandle nh_;
00135         
00136         int axis_linear_speed_, axis_angular_position_;
00137         double l_scale_, a_scale_;
00138         double current_speed_lvl;
00140         double max_linear_speed_, max_angular_position_;
00142         double desired_freq_;
00143         
00144         // TOPICS
00146         ros::Publisher vel_pub_;
00147         
00149         ros::Subscriber joy_sub_;
00151         std::string  joy_topic_;        
00153         std::string cmd_topic_vel;
00155         std::string cmd_service_io_;
00157         std::string topic_state_;
00159         ros::Publisher state_pub_;
00160 
00162         std::string service_raise_elevator_;
00164         std::string service_lower_elevator_;
00165 
00166         // SERVICES
00168         ros::ServiceServer enable_disable_srv_; 
00169         ros::ServiceClient set_digital_outputs_client_;  
00170         ros::ServiceClient raise_elevator_client_;  
00171         ros::ServiceClient lower_elevator_client_;  
00172 
00173         
00174         // JOYSTICK
00176         int num_of_buttons_;
00177         int num_of_axes_;
00178         
00180         std::vector<float> fAxes;
00182         std::vector<Button> vButtons;
00184         int button_dead_man_;
00186         int button_speed_up_, button_speed_down_;
00187         int button_up_car_, button_down_car_;
00188         int output_1_, output_2_;
00189         bool bOutput1, bOutput2;
00190                 
00191         // DIAGNOSTICS
00193         diagnostic_updater::HeaderlessTopicDiagnostic *pub_command_freq; 
00195         diagnostic_updater::HeaderlessTopicDiagnostic *sus_joy_freq; 
00197         diagnostic_updater::Updater updater_pad;        
00199         double min_freq_command, min_freq_joy; 
00201         double max_freq_command, max_freq_joy;  
00203         bool bEnable;
00204 };
00205 
00206 
00207 AgvsPad::AgvsPad():
00208   axis_linear_speed_(1),
00209   axis_angular_position_(2), nh_("~")
00210 {
00211         
00212         current_speed_lvl = 0.1;
00213         // JOYSTICK CONFIG
00214         nh_.param("num_of_buttons", num_of_buttons_, DEFAULT_NUM_OF_BUTTONS);
00215         nh_.param("num_of_axes", num_of_axes_, DEFAULT_NUM_OF_AXES);
00216         nh_.param("desired_freq", desired_freq_, DEFAULT_HZ);
00217         
00218         if(num_of_axes_ > MAX_NUM_OF_AXES){
00219                 num_of_axes_ = MAX_NUM_OF_AXES;
00220                 ROS_INFO("AgvsPad::AgvsPad: Limiting the max number of axes to %d", MAX_NUM_OF_AXES);
00221         }
00222         if(num_of_buttons_ > MAX_NUM_OF_BUTTONS){
00223                 num_of_buttons_ = MAX_NUM_OF_BUTTONS;
00224                 ROS_INFO("AgvsPad::AgvsPad: Limiting the max number of buttons to %d", MAX_NUM_OF_BUTTONS);
00225         }
00226         
00227         nh_.param("topic_joy", joy_topic_, std::string(DEFAULT_JOY));   
00228         
00229         // MOTION CONF
00230         nh_.param("cmd_topic_vel", cmd_topic_vel, std::string("/agvs_controller/command"));
00231         
00232         nh_.param("button_dead_man", button_dead_man_, button_dead_man_);
00233         nh_.param("button_speed_up", button_speed_up_, button_speed_up_);
00234         nh_.param("button_speed_down", button_speed_down_, button_speed_down_); 
00235         
00236         nh_.param("max_angular_position", max_angular_position_, DEFAULT_MAX_ANGULAR_POSITION); 
00237         nh_.param("max_linear_speed_", max_linear_speed_, DEFAULT_MAX_SKID_LINEAR_SPEED); 
00238         nh_.param("axis_linear_speed", axis_linear_speed_, DEFAULT_AXIS_LINEAR_X); 
00239         nh_.param("axis_angular_position", axis_angular_position_, DEFAULT_AXIS_ANGULAR); 
00240         ROS_INFO("axis_linear_speed_ = %d, axis_angular = %d", axis_linear_speed_, axis_angular_position_);
00241         ROS_INFO("max_linear_speed = %lf, max_angular_speed = %lf", max_linear_speed_, max_angular_position_);
00242         
00243         // DIGITAL OUTPUTS CONF
00244         nh_.param("cmd_service_io", cmd_service_io_, cmd_service_io_);
00245         nh_.param("button_up_car", button_up_car_, button_up_car_);
00246         nh_.param("button_down_car", button_down_car_, button_down_car_);
00247         nh_.param("output_1", output_1_, output_1_);
00248         nh_.param("output_2", output_2_, output_2_);
00249         
00250         nh_.param("topic_state", topic_state_, std::string("/agvs_pad/state"));
00251         
00252         nh_.param("service_raise_elevator", service_raise_elevator_, std::string("/agvs_robot_control/raise_elevator"));
00253         nh_.param("service_lower_elevator", service_lower_elevator_, std::string("/agvs_robot_control/lower_elevator"));
00254         
00255         ROS_INFO("AgvsPad num_of_buttons_ = %d, axes = %d, topic controller: %s, hz = %.2lf", num_of_buttons_, num_of_axes_, cmd_topic_vel.c_str(), desired_freq_);     
00256         
00257         for(int i = 0; i < MAX_NUM_OF_BUTTONS_PS3; i++){
00258                 Button b;
00259                 vButtons.push_back(b);
00260         }
00261         
00262         for(int i = 0; i < MAX_NUM_OF_AXES_PS3; i++){
00263                 fAxes.push_back(0.0);
00264         }
00265         
00266         //
00267         // Publish through the node handle Twist type messages to the guardian_controller/command topic
00268         //this->vel_pub_ = nh_.advertise<agvs_controller::AckermannDriveStamped>(this->cmd_topic_vel, 1);
00269         this->vel_pub_ = nh_.advertise<ackermann_msgs::AckermannDriveStamped>(this->cmd_topic_vel, 1);
00270         
00271         //
00272         // Publishes the state
00273         //state_pub_ = nh_.advertise<agvs_pad::rescuer_pad_state>(topic_state_, 1);
00274         
00275         // Listen through the node handle sensor_msgs::Joy messages from joystick 
00276         // (these are the references that we will sent to rescuer_controller/command)
00277         joy_sub_ = nh_.subscribe<sensor_msgs::Joy>(joy_topic_, 1, &AgvsPad::joyCallback, this);
00278         
00279         // Request service to activate / deactivate digital I/O
00280         set_digital_outputs_client_ = nh_.serviceClient<robotnik_msgs::set_digital_output>(cmd_service_io_);
00281 
00282     // Request raise or lower the elevator      
00283         raise_elevator_client_ = nh_.serviceClient<std_srvs::Empty>(service_raise_elevator_);
00284         lower_elevator_client_ = nh_.serviceClient<std_srvs::Empty>(service_lower_elevator_);
00285         
00286         
00287         bOutput1 = bOutput2 = false;
00288 
00289    
00290         // Diagnostics
00291         updater_pad.setHardwareID("AGVS-PAD");
00292         // Topics freq control 
00293         min_freq_command = min_freq_joy = 5.0;
00294         max_freq_command = max_freq_joy = 50.0;
00295         sus_joy_freq = new diagnostic_updater::HeaderlessTopicDiagnostic("/joy", updater_pad,
00296                             diagnostic_updater::FrequencyStatusParam(&min_freq_joy, &max_freq_joy, 0.1, 10));
00297 
00298         pub_command_freq = new diagnostic_updater::HeaderlessTopicDiagnostic(cmd_topic_vel.c_str(), updater_pad,
00299                             diagnostic_updater::FrequencyStatusParam(&min_freq_command, &max_freq_command, 0.1, 10));
00300 
00301         // Advertises new service to enable/disable the pad
00302         enable_disable_srv_ = nh_.advertiseService("/agvs_pad/enable_disable",  &AgvsPad::EnableDisable, this);
00303         //
00304         bEnable = true; // Communication flag enabled by default
00305         
00306 }
00307 
00308 
00309 /*
00310  *      \brief Updates the diagnostic component. Diagnostics
00311  *                 Publishes the state
00312  *
00313  */
00314 void AgvsPad::Update(){
00315         PublishState();
00316 }
00317 
00319 void AgvsPad::PublishState(){
00320         /*agvs_pad::rescuer_pad_state pad_state;
00321         
00322         
00323         pad_state.state = StateToString(iState);
00324         pad_state.arm_mode = ModeToString(iArmMode);
00325         pad_state.platform_mode = ModeToString(iPlatformMode);
00326         pad_state.speed_level = current_speed_lvl;
00327         pad_state.deadman_active = (bool) vButtons[button_dead_man_].IsPressed();
00328         
00329         state_pub_.publish(pad_state);*/
00330         
00331 }
00332 
00333 /*
00334  *      \brief Enables/Disables the pad
00335  *
00336  */
00337 bool AgvsPad::EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res )
00338 {
00339         bEnable = req.value;
00340 
00341         ROS_INFO("AgvsPad::EnablaDisable: Setting to %d", req.value);
00342         res.ret = true;
00343         return true;
00344 }
00345 
00346 
00347 void AgvsPad::joyCallback(const sensor_msgs::Joy::ConstPtr& joy)
00348 {
00349         
00350         // First joystick being saved
00351         for(int i = 0; i < joy->axes.size(); i++){
00352                 this->fAxes[i] = joy->axes[i];
00353         }
00354         for(int i = 0; i < joy->buttons.size(); i++){
00355                 this->vButtons[i].Press(joy->buttons[i]);
00356         }
00357         
00358         //ROS_INFO("AgvsPad::joyCallback: num_of_axes = %d, buttons = %d", (int)(joy->axes.size()), (int)(joy->buttons.size()));
00359 }
00360 
00361 
00363 void AgvsPad::ControlLoop(){
00364         double desired_linear_speed = 0.0, desired_angular_position = 0.0;
00365         //agvs_controller::AckermannDriveStamped ref_msg;
00366         ackermann_msgs::AckermannDriveStamped ref_msg;
00367         
00368         
00369         ros::Rate r(desired_freq_);   
00370 
00371     while(ros::ok()) {
00372                 
00373                 Update();
00374                         
00375                 if(bEnable){
00376                                                 
00377                         if(vButtons[button_dead_man_].IsPressed()){
00378                                 ref_msg.header.stamp = ros::Time::now();
00379                                 ref_msg.drive.jerk = 0.0; 
00380                                 ref_msg.drive.acceleration = 0.0; 
00381                                 ref_msg.drive.steering_angle_velocity = 0.0;
00382                         
00383                                 desired_linear_speed = max_linear_speed_ * current_speed_lvl * fAxes[axis_linear_speed_];
00384                                 desired_angular_position = max_angular_position_ * fAxes[axis_angular_position_];
00385                                 
00386                                 ref_msg.drive.steering_angle = desired_angular_position;
00387                                 ref_msg.drive.speed = desired_linear_speed;
00388                                 
00389                                 // Publish into command_vel topic
00390                                 vel_pub_.publish(ref_msg);
00391                         
00392                                 if(vButtons[button_speed_up_].IsReleased()){
00393                                         current_speed_lvl += 0.1;
00394                                         if(current_speed_lvl > 1.0)
00395                                                 current_speed_lvl = 1.0;
00396                                 }
00397                                 if(vButtons[button_speed_down_].IsReleased()){
00398                                         current_speed_lvl -= 0.1;
00399                                         if(current_speed_lvl < 0.0)
00400                                                 current_speed_lvl = 0.0;
00401                                 }                               
00402                                 if (vButtons[button_up_car_].IsReleased()){
00403                                         std_srvs::Empty empty_srv;
00404                                         raise_elevator_client_.call( empty_srv );
00405                                         ROS_INFO("Raise elevator");
00406                                 }
00407                                 if (vButtons[button_down_car_].IsReleased()){
00408                                         std_srvs::Empty empty_srv;
00409                                         lower_elevator_client_.call( empty_srv );
00410                                         ROS_INFO("Lower elevator");
00411                                 }
00412                                                         
00413                         }else if(vButtons[button_dead_man_].IsReleased()){
00414                                 ref_msg.header.stamp = ros::Time::now();
00415                                 ref_msg.drive.jerk = 0.0; 
00416                                 ref_msg.drive.acceleration = 0.0; 
00417                                 ref_msg.drive.steering_angle_velocity = 0.0;
00418                                 
00419                                 ref_msg.drive.steering_angle = 0.0;
00420                                 ref_msg.drive.speed = 0.0;
00421                                 //ROS_INFO("AgvsPad::ControlLoop: Deadman released!");
00422                                 vel_pub_.publish(ref_msg);// Publish into command_vel topic
00423                         }
00424                 }
00425                 
00426                 ros::spinOnce();
00427                 r.sleep();
00428         }
00429         
00430 }
00431 
00432 
00434 int main(int argc, char** argv)
00435 {
00436         ros::init(argc, argv, "agvs_pad");
00437         AgvsPad pad;
00438         
00439         pad.ControlLoop();
00440         
00441 }
00442 


agvs_pad
Author(s): Román Navarro
autogenerated on Thu Aug 27 2015 12:08:28