00001 #include "teo_hri_teleop_alg_node.h" 00002 00003 #include <wiimote/State.h> 00004 00005 TeoHriTeleopAlgNode::TeoHriTeleopAlgNode(void) : 00006 algorithm_base::IriBaseAlgorithm<TeoHriTeleopAlgorithm>() 00007 { 00008 //init class attributes if necessary 00009 //this->loop_rate_ = 2;//in [Hz] 00010 00011 // [init publishers] 00012 00013 // [init subscribers] 00014 joy_subscriber_ = public_node_handle_.subscribe("joy", 100, &TeoHriTeleopAlgNode::joy_callback, this); 00015 00016 // [init services] 00017 00018 // [init clients] 00019 get_3d_scan_client_ = public_node_handle_.serviceClient<iri_hokuyo_laser3d::Get3DScan>("get_3d_scan"); 00020 00021 // [init action servers] 00022 00023 // [init action clients] 00024 } 00025 00026 TeoHriTeleopAlgNode::~TeoHriTeleopAlgNode(void) 00027 { 00028 // [free dynamic memory] 00029 } 00030 00031 void TeoHriTeleopAlgNode::mainNodeThread(void) 00032 { 00033 // [fill msg structures] 00034 00035 // [fill srv structure and make request to the server] 00036 00037 // [fill action structure and make request to the action server] 00038 00039 // [publish messages] 00040 } 00041 00042 /* [subscriber callbacks] */ 00043 void TeoHriTeleopAlgNode::joy_callback(const sensor_msgs::Joy::ConstPtr& msg) 00044 { 00045 //ROS_INFO("TeoHriTeleopAlgNode::joy_callback: New Message Received"); 00046 00047 //use appropiate mutex to shared variables if necessary 00048 //this->alg_.lock(); 00049 //this->joy_mutex_.enter(); 00050 00051 //std::cout << msg->data << std::endl; 00052 00053 static bool first=true; 00054 00055 if(first) 00056 { 00057 prev_buttons_.resize(msg->buttons.size()); 00058 first=false; 00059 } 00060 00061 for(unsigned int i=0; i<msg->buttons.size(); i++) 00062 { 00063 if(msg->buttons[i]==1 && prev_buttons_[i]==0) 00064 useExtraButton(i); 00065 } 00066 00067 prev_buttons_ = msg->buttons; 00068 00069 //unlock previously blocked shared variables 00070 //this->alg_.unlock(); 00071 //this->joy_mutex_.exit(); 00072 } 00073 00074 bool TeoHriTeleopAlgNode::useExtraButton(const unsigned int & index) 00075 { 00076 ROS_DEBUG("Teo wiimote use extra Button"); 00077 00078 switch(index) 00079 { 00080 case wiimote::State::MSG_BTN_1: 00081 ROS_DEBUG("Button 1!"); 00082 break; 00083 00084 case wiimote::State::MSG_BTN_2: 00085 ROS_DEBUG("Button 2!"); 00086 break; 00087 00088 case wiimote::State::MSG_BTN_A: 00089 ROS_DEBUG("Button A!"); 00090 break; 00091 00092 case wiimote::State::MSG_BTN_B: 00093 ROS_DEBUG("Button B!"); 00094 break; 00095 00096 case wiimote::State::MSG_BTN_PLUS: 00097 ROS_DEBUG("Button (+)!"); 00098 break; 00099 00100 case wiimote::State::MSG_BTN_MINUS: 00101 ROS_DEBUG("Button (-)!"); 00102 break; 00103 00104 case wiimote::State::MSG_BTN_LEFT: 00105 ROS_DEBUG("Button LEFT!"); 00106 break; 00107 00108 case wiimote::State::MSG_BTN_RIGHT: 00109 ROS_DEBUG("Button RIGHT!"); 00110 break; 00111 00112 case wiimote::State::MSG_BTN_UP: 00113 ROS_DEBUG("Life UP!"); 00114 break; 00115 00116 case wiimote::State::MSG_BTN_DOWN: 00117 ROS_DEBUG("Button DOWN!"); 00118 break; 00119 00120 // case wiimote::State::MSG_BTN_Z: 00121 // ROS_DEBUG("Dragon Ball Z!"); 00122 // break; 00123 00124 // case wiimote::State::MSG_BTN_C: 00125 // ROS_DEBUG("Button C!"); 00126 // break; 00127 00128 case wiimote::State::MSG_BTN_HOME: 00129 00130 ROS_DEBUG("Button Home!"); 00131 get_3d_scan_srv_.request.request = 1; 00132 ROS_DEBUG("TeoHriTeleopAlgNode:: Sending New Request!"); 00133 if (get_3d_scan_client_.call(get_3d_scan_srv_)) 00134 { 00135 ROS_DEBUG("TeoHriTeleopAlgNode:: Response"); 00136 } 00137 else 00138 { 00139 ROS_WARN("TeoHriTeleopAlgNode:: Failed to Call Server on topic get_3d_scan "); 00140 } 00141 00142 break; 00143 00144 default: 00145 ROS_DEBUG("Button UNDEFINED!"); 00146 break; 00147 } 00148 return true; 00149 00150 } 00151 00152 /* [service callbacks] */ 00153 00154 /* [action callbacks] */ 00155 00156 /* [action requests] */ 00157 00158 void TeoHriTeleopAlgNode::node_config_update(Config &config, uint32_t level) 00159 { 00160 this->alg_.lock(); 00161 00162 this->alg_.unlock(); 00163 } 00164 00165 void TeoHriTeleopAlgNode::addNodeDiagnostics(void) 00166 { 00167 } 00168 00169 /* main function */ 00170 int main(int argc,char *argv[]) 00171 { 00172 return algorithm_base::main<TeoHriTeleopAlgNode>(argc, argv, "teo_hri_teleop_alg_node"); 00173 }