tibi_coop_alg_node.h
Go to the documentation of this file.
00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
00002 // Author 
00003 // All rights reserved.
00004 //
00005 // This file is part of iri-ros-pkg
00006 // iri-ros-pkg is free software: you can redistribute it and/or modify
00007 // it under the terms of the GNU Lesser General Public License as published by
00008 // the Free Software Foundation, either version 3 of the License, or
00009 // at your option) any later version.
00010 //
00011 // This program is distributed in the hope that it will be useful,
00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014 // GNU Lesser General Public License for more details.
00015 //
00016 // You should have received a copy of the GNU Lesser General Public License
00017 // along with this program.  If not, see <http://www.gnu.org/licenses/>.
00018 // 
00019 // IMPORTANT NOTE: This code has been generated through a script from the 
00020 // iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness
00021 // of the scripts. ROS topics can be easly add by using those scripts. Please
00022 // refer to the IRI wiki page for more information:
00023 // http://wikiri.upc.es/index.php/Robotics_Lab
00024 
00025 #ifndef _tibi_coop_alg_node_h_
00026 #define _tibi_coop_alg_node_h_
00027 
00028 #include <iri_base_algorithm/iri_base_algorithm.h>
00029 #include "tibi_coop_alg.h"
00030 
00031 // [publisher subscriber headers]
00032 #include <sensor_msgs/Joy.h>
00033 
00034 // [service client headers]
00035 #include <iri_goal_database/get_goal.h>
00036 
00037 // [action server client headers]
00038 #include <tibi_dabo_msgs/guideGoalAction.h>
00039 #include <iri_action_server/iri_action_server.h>
00040 #include <tibi_dabo_msgs/guiAction.h>
00041 #include <move_base_msgs/MoveBaseAction.h>
00042 #include <actionlib/client/simple_action_client.h>
00043 #include <actionlib/client/terminal_state.h>
00044 #include <tibi_dabo_msgs/sequenceAction.h>
00045 
00046 typedef enum {tibi_idle,tibi_wait_bored,tibi_wait_intro,tibi_set_car_goal,tibi_wait_guiding,tibi_wait_no_car,tibi_delay,tibi_wait_done,
00047               tibi_wait_car,tibi_wait_dabo,tibi_wait_home,tibi_wait_car_home} tibi_states;
00048 
00049 typedef enum {gui_none=-1,gui_set_goal=0,gui_cancel_goal} gui_cmds;
00050 
00051 typedef enum {car_none=-1,car_set_goal=0} car_cmds;
00052 
00053 typedef enum {dabo_none=-1,dabo_set_goal=0,dabo_car_done} dabo_cmds;
00054 
00055 typedef enum {tibi_none=-1,tibi_set_goal=0,tibi_car_done} tibi_cmds;
00056 
00057 typedef enum {joy_none=-1,joy_cancel_goal=0,joy_replan_goal,joy_teleop} joy_cmds;
00058 
00063 class TibiCoopAlgNode : public algorithm_base::IriBaseAlgorithm<TibiCoopAlgorithm>
00064 {
00065   private:
00066     // [publisher attributes]
00067 
00068     // [subscriber attributes]
00069     ros::Subscriber supervisor_subscriber_;
00070     void supervisor_callback(const sensor_msgs::Joy::ConstPtr& msg);
00071     CMutex supervisor_mutex_;
00072     bool new_joy_cmd;
00073     joy_cmds joy_cmd;
00074 
00075     // [service attributes]
00076 
00077     // [client attributes]
00078     ros::ServiceClient get_goal_client_;
00079     iri_goal_database::get_goal get_goal_srv_;
00080 
00081     // [action server attributes]
00082     IriActionServer<tibi_dabo_msgs::guiAction> car_tibi_action_aserver_;
00083     void car_tibi_actionStartCallback(const tibi_dabo_msgs::guiGoalConstPtr& goal);
00084     void car_tibi_actionStopCallback(void);
00085     bool car_tibi_actionIsFinishedCallback(void);
00086     bool car_tibi_actionHasSucceedCallback(void);
00087     void car_tibi_actionGetResultCallback(tibi_dabo_msgs::guiResultPtr& result);
00088     void car_tibi_actionGetFeedbackCallback(tibi_dabo_msgs::guiFeedbackPtr& feedback);
00089     bool new_car_cmd;
00090     tibi_cmds car_cmd;
00091 
00092     IriActionServer<tibi_dabo_msgs::guiAction> dabo_tibi_action_aserver_;
00093     void dabo_tibi_actionStartCallback(const tibi_dabo_msgs::guiGoalConstPtr& goal);
00094     void dabo_tibi_actionStopCallback(void);
00095     bool dabo_tibi_actionIsFinishedCallback(void);
00096     bool dabo_tibi_actionHasSucceedCallback(void);
00097     void dabo_tibi_actionGetResultCallback(tibi_dabo_msgs::guiResultPtr& result);
00098     void dabo_tibi_actionGetFeedbackCallback(tibi_dabo_msgs::guiFeedbackPtr& feedback);
00099     bool new_dabo_cmd;
00100     tibi_cmds dabo_cmd;
00101     std::string dabo_location_id;
00102 
00103     IriActionServer<tibi_dabo_msgs::guiAction> gui_action_aserver_;
00104     void gui_actionStartCallback(const tibi_dabo_msgs::guiGoalConstPtr& goal);
00105     void gui_actionStopCallback(void);
00106     bool gui_actionIsFinishedCallback(void);
00107     bool gui_actionHasSucceedCallback(void);
00108     void gui_actionGetResultCallback(tibi_dabo_msgs::guiResultPtr& result);
00109     void gui_actionGetFeedbackCallback(tibi_dabo_msgs::guiFeedbackPtr& feedback);
00110     bool new_gui_cmd;
00111     gui_cmds gui_cmd;
00112     std::string gui_location_id;
00113 
00114     // [action client attributes]
00115     actionlib::SimpleActionClient<tibi_dabo_msgs::guideGoalAction> move_guide_client_;
00116     tibi_dabo_msgs::guideGoalGoal move_guide_goal_;
00117     void move_guideMakeActionRequest();
00118     void move_guideDone(const actionlib::SimpleClientGoalState& state,  const tibi_dabo_msgs::guideGoalResultConstPtr& result);
00119     void move_guideActive();
00120     void move_guideFeedback(const tibi_dabo_msgs::guideGoalFeedbackConstPtr& feedback);
00121     bool move_guide_done;
00122 
00123     actionlib::SimpleActionClient<tibi_dabo_msgs::guiAction> tibi_car_action_client_;
00124     tibi_dabo_msgs::guiGoal tibi_car_action_goal_;
00125     bool tibi_car_actionMakeActionRequest();
00126     void tibi_car_actionDone(const actionlib::SimpleClientGoalState& state,  const tibi_dabo_msgs::guiResultConstPtr& result);
00127     void tibi_car_actionActive();
00128     void tibi_car_actionFeedback(const tibi_dabo_msgs::guiFeedbackConstPtr& feedback);
00129     bool tibi_car_action_done;
00130 
00131     actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> move_base_client_;
00132     move_base_msgs::MoveBaseGoal move_base_goal_;
00133     bool move_baseMakeActionRequest();
00134     void move_baseDone(const actionlib::SimpleClientGoalState& state,  const move_base_msgs::MoveBaseResultConstPtr& result);
00135     void move_baseActive();
00136     void move_baseFeedback(const move_base_msgs::MoveBaseFeedbackConstPtr& feedback);
00137     bool move_base_done;
00138 
00139     actionlib::SimpleActionClient<tibi_dabo_msgs::sequenceAction> hri_client_client_;
00140     tibi_dabo_msgs::sequenceGoal hri_client_goal_;
00141     bool hri_clientMakeActionRequest();
00142     void hri_clientDone(const actionlib::SimpleClientGoalState& state,  const tibi_dabo_msgs::sequenceResultConstPtr& result);
00143     void hri_clientActive();
00144     void hri_clientFeedback(const tibi_dabo_msgs::sequenceFeedbackConstPtr& feedback);
00145     bool hri_client_done;
00146 
00147     // [class attributes]
00148     tibi_states current_state;
00149     std::vector< std::vector < std::string > > sentences;
00150 
00151     void loadSentences();
00152 
00153   public:
00160     TibiCoopAlgNode(void);
00161 
00168     ~TibiCoopAlgNode(void);
00169 
00170   protected:
00183     void mainNodeThread(void);
00184 
00197     void node_config_update(Config &config, uint32_t level);
00198 
00205     void addNodeDiagnostics(void);
00206 
00207     // [diagnostic functions]
00208     
00209     // [test functions]
00210 };
00211 
00212 #endif


tibi_coop
Author(s): Sergi Hernandez Juan
autogenerated on Fri Dec 6 2013 21:28:54