Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #ifndef _tibi_dabo_hri_alg_node_h_
00026 #define _tibi_dabo_hri_alg_node_h_
00027
00028 #include <iri_base_algorithm/iri_base_algorithm.h>
00029 #include "tibi_dabo_hri_alg.h"
00030
00031
00032 #include <std_msgs/String.h>
00033
00034
00035
00036
00037 #include <iri_action_server/iri_action_server.h>
00038 #include <tibi_dabo_msgs/sequenceAction.h>
00039 #include <actionlib/client/simple_action_client.h>
00040 #include <actionlib/client/terminal_state.h>
00041 #include <iri_common_drivers_msgs/ttsAction.h>
00042
00043 typedef enum {TTS_=0,LEDS_=1,HEAD_=2,LEFT_ARM_=3,RIGHT_ARM_=4} clients;
00044 static const unsigned int NUM_CLIENTS=RIGHT_ARM_-TTS_+1;
00045
00046 typedef actionlib::SimpleActionClient<tibi_dabo_msgs::sequenceAction> SeqClient;
00047
00048 typedef struct
00049 {
00050 SeqClient *client;
00051 bool succeeded;
00052 bool active;
00053 bool loaded;
00054 float percentage;
00055 }TSeqClient;
00056
00057 typedef actionlib::SimpleActionClient<iri_common_drivers_msgs::ttsAction> TtsClient;
00058
00059 typedef struct
00060 {
00061 TtsClient *client;
00062 bool succeeded;
00063 bool active;
00064 bool loaded;
00065 float percentage;
00066 }TTtsClient;
00071 class TibiDaboHriAlgNode : public algorithm_base::IriBaseAlgorithm<TibiDaboHriAlgorithm>
00072 {
00073 private:
00074
00075 ros::Publisher facial_expression_publisher_;
00076
00077
00078
00079
00080
00081
00082
00083
00084 IriActionServer<tibi_dabo_msgs::sequenceAction> seqs_aserver_;
00085 void startCallback(const tibi_dabo_msgs::sequenceGoalConstPtr& goal);
00086 void stopCallback(void);
00087 bool isFinishedCallback(void);
00088 bool hasSucceedCallback(void);
00089 void getResultCallback(tibi_dabo_msgs::sequenceResultPtr& result);
00090 void getFeedbackCallback(tibi_dabo_msgs::sequenceFeedbackPtr& feedback);
00091
00092
00093
00094 TTtsClient tts_;
00095 void ttsMakeActionRequest(const iri_common_drivers_msgs::ttsGoal & tts_goal);
00096 void ttsDone(const actionlib::SimpleClientGoalState& state, const iri_common_drivers_msgs::ttsResultConstPtr& result);
00097 void ttsActive(void);
00098 void ttsFeedback(const iri_common_drivers_msgs::ttsFeedbackConstPtr& feedback);
00099
00100
00101 TSeqClient leds_;
00102 void ledsMakeActionRequest(const tibi_dabo_msgs::sequenceGoal & leds_goal);
00103 void ledsDone(const actionlib::SimpleClientGoalState& state, const tibi_dabo_msgs::sequenceResultConstPtr& result);
00104 void ledsActive(void);
00105 void ledsFeedback(const tibi_dabo_msgs::sequenceFeedbackConstPtr& feedback);
00106
00107
00108 TSeqClient head_;
00109 void headMakeActionRequest(const tibi_dabo_msgs::sequenceGoal & head_goal);
00110 void headDone(const actionlib::SimpleClientGoalState& state, const tibi_dabo_msgs::sequenceResultConstPtr& result);
00111 void headActive(void);
00112 void headFeedback(const tibi_dabo_msgs::sequenceFeedbackConstPtr& feedback);
00113
00114
00115 TSeqClient left_arm_;
00116 void leftArmMakeActionRequest(const tibi_dabo_msgs::sequenceGoal & left_arm_goal);
00117 void leftArmDone(const actionlib::SimpleClientGoalState& state, const tibi_dabo_msgs::sequenceResultConstPtr& result);
00118 void leftArmActive(void);
00119 void leftArmFeedback(const tibi_dabo_msgs::sequenceFeedbackConstPtr& feedback);
00120
00121
00122 TSeqClient right_arm_;
00123 void rightArmMakeActionRequest(const tibi_dabo_msgs::sequenceGoal & right_arm_goal);
00124 void rightArmDone(const actionlib::SimpleClientGoalState& state, const tibi_dabo_msgs::sequenceResultConstPtr& result);
00125 void rightArmActive(void);
00126 void rightArmFeedback(const tibi_dabo_msgs::sequenceFeedbackConstPtr& feedback);
00127
00128
00129 bool empty_leds_sequence_;
00130 bool tts_connected_;
00131 bool leds_connected_;
00132 bool head_connected_;
00133 bool left_arm_connected_;
00134 bool right_arm_connected_;
00135
00136 public:
00143 TibiDaboHriAlgNode(void);
00144
00151 ~TibiDaboHriAlgNode(void);
00152
00153 protected:
00166 void mainNodeThread(void);
00167
00180 void node_config_update(Config &config, uint32_t level);
00181
00188 void addNodeDiagnostics(void);
00189
00190
00191
00192
00193
00194 void cancelCurrentGoals(void);
00195 void speak(void);
00196 };
00197
00198 #endif