00001 /* Software License Agreement (BSD License) 00002 * 00003 * Copyright (c) 2014, Robotiq, Inc. 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions 00008 * are met: 00009 * 00010 * * Redistributions of source code must retain the above copyright 00011 * notice, this list of conditions and the following disclaimer. 00012 * * Redistributions in binary form must reproduce the above 00013 * copyright notice, this list of conditions and the following 00014 * disclaimer in the documentation and/or other materials provided 00015 * with the distribution. 00016 * * Neither the name of Robotiq, Inc. nor the names of its 00017 * contributors may be used to endorse or promote products derived 00018 * from this software without specific prior written permission. 00019 * 00020 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 * POSSIBILITY OF SUCH DAMAGE. 00032 * 00033 * Copyright (c) 2014, Robotiq, Inc 00034 */ 00035 00036 /* 00037 * \file rq_sensor_state.c 00038 * \date June 19, 2014 00039 * \author Jonathan Savoie <jonathan.savoie@robotiq.com> 00040 * \maintainer Nicolas Lauzier <nicolas@robotiq.com> 00041 */ 00042 00044 //Includes 00045 #include <string.h> 00046 #include "robotiq_force_torque_sensor/rq_sensor_state.h" 00047 #include "robotiq_force_torque_sensor/rq_sensor_com.h" 00048 00050 //Private variables 00051 static enum rq_sensor_state_values current_state = RQ_STATE_INIT; 00052 00054 //Private functions 00055 static INT_8 rq_state_init_com(); 00056 static void rq_state_read_info_high_lvl(); 00057 static void rq_state_start_stream(); 00058 static void rq_state_run(unsigned int max_retries); 00059 00061 //Function definitions 00062 00068 INT_8 rq_sensor_state(unsigned int max_retries) 00069 { 00070 INT_8 ret; 00071 00072 switch (current_state) 00073 { 00074 case RQ_STATE_INIT: 00075 ret = rq_state_init_com(); 00076 if(ret == -1) 00077 { 00078 return -1; 00079 } 00080 break; 00081 00082 case RQ_STATE_READ_INFO: 00083 rq_state_read_info_high_lvl(); 00084 break; 00085 00086 case RQ_STATE_START_STREAM: 00087 rq_state_start_stream(); 00088 break; 00089 00090 case RQ_STATE_RUN: 00091 rq_state_run(max_retries); 00092 break; 00093 00094 default: 00095 printf("rq_state(): Unknown error\r\n"); 00096 return -1; 00097 break; 00098 00099 } 00100 return 0; 00101 } 00102 00108 static INT_8 rq_state_init_com() 00109 { 00110 if(rq_sensor_com() == -1) 00111 { 00112 return -1; 00113 } 00114 00115 current_state = RQ_STATE_READ_INFO; 00116 return 0; 00117 } 00118 00125 static void rq_state_read_info_high_lvl() 00126 { 00127 rq_sensor_com_read_info_high_lvl(); 00128 current_state = RQ_STATE_START_STREAM; 00129 } 00130 00137 static void rq_state_start_stream() 00138 { 00139 if(rq_com_start_stream() == -1) 00140 { 00141 #if defined(_WIN32)||defined(WIN32) //For Windows 00142 stop_connection(); 00143 #endif 00144 current_state = RQ_STATE_INIT; 00145 } 00146 current_state = RQ_STATE_RUN; 00147 } 00148 00155 static void rq_state_run(unsigned int max_retries) 00156 { 00157 static unsigned int retries = 0; 00158 00159 rq_com_listen_stream(); 00160 00161 if(rq_com_get_valid_stream() == false) 00162 { 00163 retries++; 00164 if (retries >= max_retries) 00165 { 00166 #if defined(_WIN32)||defined(WIN32) //For Windows 00167 stop_connection(); 00168 #endif 00169 current_state = RQ_STATE_INIT; 00170 retries = 0; 00171 } 00172 } 00173 else 00174 { 00175 retries = 0; 00176 } 00177 } 00178 00185 float rq_state_get_received_data(UINT_8 i) 00186 { 00187 if(i >= 0 && i <= 5) 00188 { 00189 return rq_com_get_received_data(i); 00190 } 00191 else 00192 { 00193 return 0.0; 00194 } 00195 } 00196 00205 void rq_state_get_command(INT_8 const * const name, INT_8 * const value) 00206 { 00207 //precondition, null pointer 00208 if( value == NULL || name == NULL) 00209 { 00210 return; 00211 } 00212 00213 if(strstr(name, "SNU")) 00214 { 00215 rq_com_get_str_serial_number( value); 00216 } 00217 else if(strstr(name, "FWV")) 00218 { 00219 rq_com_get_str_firmware_version( value); 00220 } 00221 else if(strstr(name, "PYE")) 00222 { 00223 rq_com_get_str_production_year( value); 00224 } 00225 } 00226 00231 enum rq_sensor_state_values rq_sensor_get_current_state() 00232 { 00233 return current_state; 00234 } 00235 00239 bool rq_state_got_new_message() 00240 { 00241 return rq_com_got_new_message(); 00242 } 00243 00247 void rq_state_do_zero_force_flag() 00248 { 00249 rq_com_do_zero_force_flag(); 00250 }