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 _people_follower_alg_node_h_ 00026 #define _people_follower_alg_node_h_ 00027 00028 #include <iri_base_algorithm/iri_base_algorithm.h> 00029 #include "people_follower_alg.h" 00030 00031 // [publisher subscriber headers] 00032 #include <geometry_msgs/PoseStamped.h> 00033 #include <iri_people_tracking/peopleTrackingArray.h> 00034 00035 // [service client headers] 00036 00037 // [action server client headers] 00038 #include <iri_action_server/iri_action_server.h> 00039 #include <iri_nav_msgs/followTargetAction.h> 00040 #include <actionlib/client/simple_action_client.h> 00041 #include <actionlib/client/terminal_state.h> 00042 #include <move_base_msgs/MoveBaseAction.h> 00043 00044 #include "eventserver.h" 00045 00050 class PeopleFollowerAlgNode : public algorithm_base::IriBaseAlgorithm<PeopleFollowerAlgorithm> 00051 { 00052 private: 00053 // [publisher attributes] 00054 00055 // [subscriber attributes] 00056 ros::Subscriber target_pose_subscriber_; 00057 void target_pose_callback(const geometry_msgs::PoseStamped::ConstPtr& msg); 00058 CMutex target_pose_mutex_; 00059 00060 // [service attributes] 00061 00062 // [client attributes] 00063 00064 // [action server attributes] 00065 IriActionServer<iri_nav_msgs::followTargetAction> followTarget_aserver_; 00066 void followTargetStartCallback(const iri_nav_msgs::followTargetGoalConstPtr& goal); 00067 void followTargetStopCallback(void); 00068 bool followTargetIsFinishedCallback(void); 00069 bool followTargetHasSucceedCallback(void); 00070 void followTargetGetResultCallback(iri_nav_msgs::followTargetResultPtr& result); 00071 void followTargetGetFeedbackCallback(iri_nav_msgs::followTargetFeedbackPtr& feedback); 00072 00073 // [action client attributes] 00074 actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> moveBase_client_; 00075 void moveBaseMakeActionRequest(const move_base_msgs::MoveBaseGoal & goal); 00076 void moveBaseDone(const actionlib::SimpleClientGoalState& state, const move_base_msgs::MoveBaseResultConstPtr& result); 00077 void moveBaseActive(); 00078 void moveBaseFeedback(const move_base_msgs::MoveBaseFeedbackConstPtr& feedback); 00079 00080 // Event server manager 00081 CEventServer * event_server_; 00082 00083 // Events identifiers 00084 std::string new_req_event_id_; 00085 std::string moveBase_done_event_id_; 00086 std::string moveBase_preempt_event_id_; 00087 std::string target_pose_received_event_id_; 00088 std::string follow_target_done_event_id_; 00089 00090 typedef enum {IDLE_STATE, REQ_MB_STATE, FOLLOWING_STATE, SUCCESS_STATE, UPDATE_STATE, PREEMPT_STATE} states; 00091 states current_state_; 00092 00093 unsigned int request_id_; 00094 float dist_to_goal_; 00095 unsigned int no_target_pose_msg_received_; 00096 static const unsigned int MAX_ITERS_NO_MSG = 200; 00097 00098 std::string tf_prefix_; 00099 std::string target_frame_; 00100 std::string fixed_frame_; 00101 00102 geometry_msgs::PoseStamped global_target_goal_; 00103 geometry_msgs::PoseStamped current_global_target_pose_; 00104 00105 public: 00112 PeopleFollowerAlgNode(void); 00113 00120 ~PeopleFollowerAlgNode(void); 00121 00122 protected: 00135 void mainNodeThread(void); 00136 00149 void node_config_update(Config &config, uint32_t level); 00150 00157 void addNodeDiagnostics(void); 00158 00159 // [diagnostic functions] 00160 00161 // [test functions] 00162 }; 00163 00164 #endif