$search
00001 /**************************************************************** 00002 * 00003 * Copyright (c) 2010 00004 * 00005 * Fraunhofer Institute for Manufacturing Engineering 00006 * and Automation (IPA) 00007 * 00008 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00009 * 00010 * Project name: care-o-bot 00011 * ROS stack name: cob_driver 00012 * ROS package name: cob_relayboard 00013 * Description: Reads and sends data over Serial Interface to the Serial Relayboard. Main Tasks: Reading of EmergencyStop and LaserScannerStop 00014 * 00015 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00016 * 00017 * Author: Philipp Koehler 00018 * Supervised by: Christian Connette, email:christian.connette@ipa.fhg.de 00019 * 00020 * Date of creation: March 2010 00021 * ToDo: 00022 * 00023 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00024 * 00025 * Redistribution and use in source and binary forms, with or without 00026 * modification, are permitted provided that the following conditions are met: 00027 * 00028 * * Redistributions of source code must retain the above copyright 00029 * notice, this list of conditions and the following disclaimer. 00030 * * Redistributions in binary form must reproduce the above copyright 00031 * notice, this list of conditions and the following disclaimer in the 00032 * documentation and/or other materials provided with the distribution. 00033 * * Neither the name of the Fraunhofer Institute for Manufacturing 00034 * Engineering and Automation (IPA) nor the names of its 00035 * contributors may be used to endorse or promote products derived from 00036 * this software without specific prior written permission. 00037 * 00038 * This program is free software: you can redistribute it and/or modify 00039 * it under the terms of the GNU Lesser General Public License LGPL as 00040 * published by the Free Software Foundation, either version 3 of the 00041 * License, or (at your option) any later version. 00042 * 00043 * This program is distributed in the hope that it will be useful, 00044 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00045 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00046 * GNU Lesser General Public License LGPL for more details. 00047 * 00048 * You should have received a copy of the GNU Lesser General Public 00049 * License LGPL along with this program. 00050 * If not, see <http://www.gnu.org/licenses/>. 00051 * 00052 ****************************************************************/ 00053 00054 //################## 00055 //#### includes #### 00056 00057 // standard includes 00058 //-- 00059 00060 // ROS includes 00061 #include <ros/ros.h> 00062 #include <cob_relayboard/SerRelayBoard.h> 00063 00064 // ROS message includes 00065 #include <std_msgs/Bool.h> 00066 #include <std_msgs/Float64.h> 00067 #include <cob_relayboard/EmergencyStopState.h> 00068 #include <pr2_msgs/PowerState.h> 00069 #include <pr2_msgs/PowerBoardState.h> 00070 00071 00072 // ROS service includes 00073 //-- 00074 00075 // external includes 00076 //-- 00077 00078 //#################### 00079 //#### node class #### 00080 class NodeClass 00081 { 00082 // 00083 public: 00084 // create a handle for this node, initialize node 00085 ros::NodeHandle n; 00086 00087 // topics to publish 00088 ros::Publisher topicPub_isEmergencyStop; 00089 ros::Publisher topicPub_PowerState; 00090 ros::Publisher topicPub_PowerBoardState; 00091 ros::Publisher topicPub_Voltage; 00092 // topics to subscribe, callback is called for new messages arriving 00093 // -- 00094 00095 // Constructor 00096 NodeClass() 00097 { 00098 n = ros::NodeHandle("~"); 00099 00100 topicPub_isEmergencyStop = n.advertise<cob_relayboard::EmergencyStopState>("/emergency_stop_state", 1); 00101 topicPub_PowerState = n.advertise<pr2_msgs::PowerState>("/power_state", 1); 00102 topicPub_PowerBoardState = n.advertise<pr2_msgs::PowerBoardState>("/power_board/state", 1); 00103 topicPub_Voltage = n.advertise<std_msgs::Float64>("/power_board/voltage", 10); 00104 00105 // Make sure member variables have a defined state at the beginning 00106 EM_stop_status_ = ST_EM_FREE; 00107 relayboard_available = false; 00108 relayboard_online = false; 00109 relayboard_timeout_ = 2.0; 00110 voltage_offset_ = 2.0; 00111 voltage_min_ = 48.0; 00112 voltage_max_ = 56.0; 00113 protocol_version_ = 1; 00114 duration_for_EM_free_ = ros::Duration(1); 00115 } 00116 00117 // Destructor 00118 ~NodeClass() 00119 { 00120 delete m_SerRelayBoard; 00121 } 00122 00123 void sendEmergencyStopStates(); 00124 void sendBatteryVoltage(); 00125 int init(); 00126 00127 private: 00128 std::string sComPort; 00129 SerRelayBoard * m_SerRelayBoard; 00130 00131 int EM_stop_status_; 00132 ros::Duration duration_for_EM_free_; 00133 ros::Time time_of_EM_confirmed_; 00134 double relayboard_timeout_; 00135 double voltage_offset_; 00136 double voltage_min_; 00137 double voltage_max_; 00138 int protocol_version_; 00139 00140 ros::Time time_last_message_received_; 00141 bool relayboard_online; //the relayboard is sending messages at regular time 00142 bool relayboard_available; //the relayboard has sent at least one message -> publish topic 00143 00144 // possible states of emergency stop 00145 enum 00146 { 00147 ST_EM_FREE = 0, 00148 ST_EM_ACTIVE = 1, 00149 ST_EM_CONFIRMED = 2 00150 }; 00151 00152 int requestBoardStatus(); 00153 }; 00154 00155 //####################### 00156 //#### main programm #### 00157 int main(int argc, char** argv) 00158 { 00159 // initialize ROS, spezify name of node 00160 ros::init(argc, argv, "cob_relayboard_node"); 00161 00162 NodeClass node; 00163 if(node.init() != 0) return 1; 00164 00165 ros::Rate r(20); //Cycle-Rate: Frequency of publishing EMStopStates 00166 while(node.n.ok()) 00167 { 00168 node.sendEmergencyStopStates(); 00169 00170 ros::spinOnce(); 00171 r.sleep(); 00172 } 00173 00174 return 0; 00175 } 00176 00177 //################################## 00178 //#### function implementations #### 00179 00180 int NodeClass::init() 00181 { 00182 if (n.hasParam("ComPort")) 00183 { 00184 n.getParam("ComPort", sComPort); 00185 ROS_INFO("Loaded ComPort parameter from parameter server: %s",sComPort.c_str()); 00186 } 00187 else 00188 { 00189 sComPort ="/dev/ttyUSB0"; 00190 ROS_WARN("ComPort Parameter not available, using default Port: %s",sComPort.c_str()); 00191 } 00192 00193 n.param("relayboard_timeout", relayboard_timeout_, 2.0); 00194 n.param("relayboard_voltage_offset", voltage_offset_, 2.0); 00195 n.param("cob3_min_voltage", voltage_min_, 48.0); 00196 n.param("cob3_max_voltage", voltage_max_, 56.0); 00197 00198 n.param("protocol_version", protocol_version_, 1); 00199 00200 m_SerRelayBoard = new SerRelayBoard(sComPort, protocol_version_); 00201 ROS_INFO("Opened Relayboard at ComPort = %s", sComPort.c_str()); 00202 00203 m_SerRelayBoard->init(); 00204 00205 // Init member variable for EM State 00206 EM_stop_status_ = ST_EM_ACTIVE; 00207 duration_for_EM_free_ = ros::Duration(1); 00208 00209 return 0; 00210 } 00211 00212 int NodeClass::requestBoardStatus() { 00213 int ret; 00214 00215 // Request Status of RelayBoard 00216 ret = m_SerRelayBoard->sendRequest(); 00217 if(ret != SerRelayBoard::NO_ERROR) { 00218 ROS_ERROR("Error in sending message to Relayboard over SerialIO, lost bytes during writing"); 00219 } 00220 00221 ret = m_SerRelayBoard->evalRxBuffer(); 00222 if(ret==SerRelayBoard::NOT_INITIALIZED) { 00223 ROS_ERROR("Failed to read relayboard data over Serial, the device is not initialized"); 00224 relayboard_online = false; 00225 } else if(ret==SerRelayBoard::NO_MESSAGES) { 00226 ROS_ERROR("For a long time, no messages from RelayBoard have been received, check com port!"); 00227 if(time_last_message_received_.toSec() - ros::Time::now().toSec() > relayboard_timeout_) {relayboard_online = false;} 00228 } else if(ret==SerRelayBoard::TOO_LESS_BYTES_IN_QUEUE) { 00229 //ROS_ERROR("Relayboard: Too less bytes in queue"); 00230 } else if(ret==SerRelayBoard::CHECKSUM_ERROR) { 00231 ROS_ERROR("A checksum error occurred while reading from relayboard data"); 00232 } else if(ret==SerRelayBoard::NO_ERROR) { 00233 relayboard_online = true; 00234 relayboard_available = true; 00235 time_last_message_received_ = ros::Time::now(); 00236 } 00237 00238 return 0; 00239 } 00240 00241 void NodeClass::sendBatteryVoltage() 00242 { 00243 ROS_DEBUG("Current Battery Voltage: %f", (m_SerRelayBoard->getBatteryVoltage()/1000.0) + voltage_offset_); 00244 double percentage = ((m_SerRelayBoard->getBatteryVoltage()/1000.0) + voltage_offset_ - voltage_min_) * 100/(voltage_max_ - voltage_min_); 00245 //Not supported by relayboard 00246 //ROS_INFO("Current Charge current: %d", m_SerRelayBoard->getChargeCurrent()); 00247 //--- 00248 pr2_msgs::PowerState ps; 00249 ps.header.stamp = ros::Time::now(); 00250 ps.power_consumption = 0.0; 00251 ps.time_remaining = ros::Duration(1000); //TODO: Needs to be calculated based on battery type (plumb or lithion-ion), maybe specify charging characteristics in table in .yaml file 00252 ps.relative_capacity = percentage; // TODO: Needs to be calculated based on battery type (plumb or lithion-ion), maybe specify charging characteristics in table in .yaml file 00253 topicPub_PowerState.publish(ps); 00254 00255 std_msgs::Float64 voltage; 00256 // std::cout << m_SerRelayBoard->getBatteryVoltage() << std::endl; 00257 voltage.data = m_SerRelayBoard->getBatteryVoltage(); 00258 topicPub_Voltage.publish(voltage); 00259 00260 } 00261 00262 void NodeClass::sendEmergencyStopStates() 00263 { 00264 requestBoardStatus(); 00265 00266 if(!relayboard_available) return; 00267 00268 sendBatteryVoltage(); 00269 00270 00271 bool EM_signal; 00272 ros::Duration duration_since_EM_confirmed; 00273 cob_relayboard::EmergencyStopState EM_msg; 00274 pr2_msgs::PowerBoardState pbs; 00275 pbs.header.stamp = ros::Time::now(); 00276 00277 // assign input (laser, button) specific EM state TODO: Laser and Scanner stop can't be read independently (e.g. if button is stop --> no informtion about scanner, if scanner ist stop --> no informtion about button stop) 00278 EM_msg.emergency_button_stop = m_SerRelayBoard->isEMStop(); 00279 EM_msg.scanner_stop = m_SerRelayBoard->isScannerStop(); 00280 00281 // determine current EMStopState 00282 EM_signal = (EM_msg.emergency_button_stop || EM_msg.scanner_stop); 00283 00284 switch (EM_stop_status_) 00285 { 00286 case ST_EM_FREE: 00287 { 00288 if (EM_signal == true) 00289 { 00290 ROS_INFO("Emergency stop was issued"); 00291 EM_stop_status_ = EM_msg.EMSTOP; 00292 } 00293 break; 00294 } 00295 case ST_EM_ACTIVE: 00296 { 00297 if (EM_signal == false) 00298 { 00299 ROS_INFO("Emergency stop was confirmed"); 00300 EM_stop_status_ = EM_msg.EMCONFIRMED; 00301 time_of_EM_confirmed_ = ros::Time::now(); 00302 } 00303 break; 00304 } 00305 case ST_EM_CONFIRMED: 00306 { 00307 if (EM_signal == true) 00308 { 00309 ROS_INFO("Emergency stop was issued"); 00310 EM_stop_status_ = EM_msg.EMSTOP; 00311 } 00312 else 00313 { 00314 duration_since_EM_confirmed = ros::Time::now() - time_of_EM_confirmed_; 00315 if( duration_since_EM_confirmed.toSec() > duration_for_EM_free_.toSec() ) 00316 { 00317 ROS_INFO("Emergency stop released"); 00318 EM_stop_status_ = EM_msg.EMFREE; 00319 } 00320 } 00321 break; 00322 } 00323 }; 00324 00325 00326 EM_msg.emergency_state = EM_stop_status_; 00327 00328 // pr2 power_board_state 00329 if(EM_msg.emergency_button_stop) 00330 pbs.run_stop = false; 00331 else 00332 pbs.run_stop = true; 00333 00334 //for cob the wireless stop field is misused as laser stop field 00335 if(EM_msg.scanner_stop) 00336 pbs.wireless_stop = false; 00337 else 00338 pbs.wireless_stop = true; 00339 00340 00341 //publish EM-Stop-Active-messages, when connection to relayboard got cut 00342 if(relayboard_online == false) { 00343 EM_msg.emergency_state = EM_msg.EMSTOP; 00344 } 00345 topicPub_isEmergencyStop.publish(EM_msg); 00346 topicPub_PowerBoardState.publish(pbs); 00347 }