$search
00001 /* 00002 * Copyright (c) 2011, Robert Bosch LLC 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of Robert Bosch LLC nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 /* 00031 * Smi540.cpp 00032 * 00033 * Created on: Jul 27, 2011 00034 * Author: Lucas Marti, Robert Bosch LLC | 00035 * Author: Nikhil Deshpande, Robert Bosch LLC | 00036 */ 00037 00038 #include <iostream> 00039 #include <string> 00040 #include <ros/ros.h> 00041 #include "smi540/smi540.h" 00042 #include <sstream> 00043 #include <ros/time.h> 00044 #include <math.h> 00045 #include <vector> 00046 00047 Smi540::Smi540(std::string sSub20Serial): 00048 bSubDeviceOpen (false), 00049 bSubDeviceConfigured (false), 00050 strSerial (" ") 00051 { 00052 int spi_error_code; //Error code for Sub20 API 00053 int iSPI_cfg_set; //Set SPI config 00054 int iSPI_cfg_get; //Get SPI config 00055 sub_device sub20dev; 00056 sub_handle sub20handle; 00057 std::cout << "---opening SUB device---" << " \n"; 00058 std::string sub20serial; 00059 OneSub20Config OneSub20Configuration; 00060 00062 // Open connected Sub20 Devices 00064 sub20dev = 0; 00065 sub20dev = sub_find_devices(sub20dev); 00066 std::cout << "sub 20 Device: " << sub20dev << std::endl; 00067 while( sub20dev != 0 ) 00068 { 00069 sub20handle = sub_open(sub20dev); 00070 // on success, sub_open returns non-zero handle 00071 if( sub20handle == 0 ) 00072 { 00073 //sub_open was not successful 00074 ROS_INFO("ERROR - Sub20 could not be opened: %s ", sub_strerror(sub_errno) ); 00075 } 00076 else 00077 { 00078 //Subdevice successfully opened 00079 sub20serial.clear(); 00080 sub20serial.resize( smi540_cmd::uSERIALNUMLENGTH ); 00081 sub_get_serial_number(sub20handle, const_cast<char*>(sub20serial.c_str()), sub20serial.size()); 00082 std::cout << "Serial Number : " << sub20serial << std::endl; 00083 // Compare if the opened sub20 device is the one desired! 00084 if( strcmp(sub20serial.c_str(), sSub20Serial.c_str()) == 0 ) 00085 { 00087 // Configure Sub20 device 00089 subhndl = sub20handle; 00090 bSubDeviceOpen = true; 00091 std::cout << "---Initializing SPI Interface---" << std::endl; 00092 /* Read current SPI configuration */ 00093 spi_error_code = sub_spi_config( sub20handle, 0, &iSPI_cfg_get ); 00094 std::cout << "Dev Sub config : " << iSPI_cfg_get << " \n"; 00095 //Important: The SPI interface does not work properly at higher frequencies 00096 iSPI_cfg_set = SPI_ENABLE|SPI_CPOL_RISE|SPI_SMPL_SETUP|SPI_MSB_FIRST|SPI_CLK_1MHZ; 00097 /* Configure SPI */ 00098 spi_error_code = sub_spi_config( sub20handle, iSPI_cfg_set, 0 ); 00099 /* Read current SPI configuration */ 00100 spi_error_code = sub_spi_config( sub20handle, 0, &iSPI_cfg_get ); 00101 00102 //verify if sub20 device has accepted the configuration 00103 if( iSPI_cfg_get == iSPI_cfg_set ) 00104 { 00105 bSubDeviceConfigured = true; 00106 std::cout<< "Configuration : " << iSPI_cfg_set << " successfully stored \n"; 00107 //Subdevice has been configured successfully 00108 OneSub20Configuration.bSubSPIConfigured = true; 00109 OneSub20Configuration.handle_subdev = sub20handle; 00111 // Configure Sensors on Sub20 00113 std::cout<< "Configuring SMI540 device" << std::endl; 00114 confsens_on_sub20( &OneSub20Configuration); 00115 } 00116 else 00117 { 00118 std::cout<< "ERROR - Configuration :" << iSPI_cfg_set << " not accept by device \n"; 00119 //Subdevice could not be configured 00120 bSubDeviceConfigured = false; 00121 OneSub20Configuration.bSubSPIConfigured = false; 00122 } 00123 00124 //only execute if SubDevice has accepted configuration 00125 if( OneSub20Configuration.bSubSPIConfigured ) 00126 { 00127 // SS_CONF(0,SS_LO): 00128 // SS_N Chipselect 0; 00129 // SS_LO SS goes low and stays low during entire transfer, after that it goes high 00130 spi_error_code = sub_spi_transfer( sub20handle, smi540_cmd::chTRIGGER_RESET, 0, 4, SS_CONF(0,SS_LO) ); 00131 strSerial.clear(); 00132 strSerial.resize( smi540_cmd::uSERIALNUMLENGTH ); 00133 sub_get_serial_number( sub20handle, const_cast<char*>(strSerial.c_str()), strSerial.size() ); 00134 OneSub20Configuration.strSub20Serial = strSerial; 00135 OneSub20Configuration.subdev = sub20dev; 00136 std::cout << "Device Handle : " << OneSub20Configuration.handle_subdev << std::endl; 00137 std::cout << "Serial Number : " << OneSub20Configuration.strSub20Serial << std::endl; 00139 // Push element onto list of subdevices 00141 Sub20Device_list.push_back (OneSub20Configuration); 00142 std::cout << "... Publishing to topic /smi540 ... " << std::endl; 00143 } 00144 break; 00145 } 00146 else 00147 { 00148 sub_close( sub20handle ); 00149 } 00150 } 00151 //find next device, sub_find_devices using current provides next 00152 sub20dev = sub_find_devices( sub20dev ); 00153 } 00154 }; 00155 00156 Smi540::~Smi540() 00157 { 00158 int spi_error_code; 00159 OneSub20Config OneSub20Configuration; 00160 // Disable SPI 00161 spi_error_code = sub_spi_config( subhndl, 0, 0 ); 00162 // Close USB device 00163 sub_close( subhndl ); 00164 //Set status 00165 bSubDeviceOpen = false; 00166 bSubDeviceConfigured = false; 00167 while( !Sub20Device_list.empty() ) 00168 { 00169 OneSub20Configuration = Sub20Device_list.back(); 00170 std::cout << "Sub device removed " << OneSub20Configuration.strSub20Serial << "\n"; 00171 Sub20Device_list.pop_back(); 00172 } 00173 }; 00174 00175 00176 void Smi540::GetMeasurements( std::list<OneSmi540Meas> &list_meas ) 00177 { 00178 char chMM5_rx[8], chCMD; //Containing 00179 int spi_error_code, iChipSelect, j = 0; 00180 OneSmi540Meas sMeas; 00181 unsigned short smi540health; 00182 double dAccX, dAccY, dRateZ; 00183 bool SPIMeas = false; 00184 std::list<OneSub20Config>::iterator iterat; 00185 00186 //verify that a subdevice is connected 00187 if( 1 > (int)Sub20Device_list.size() ) 00188 { 00189 throw std::string ("No SubDevice connected OR access rights to USB not given"); 00190 } 00191 //Trace sub20 list 00192 for( iterat = Sub20Device_list.begin(); iterat != Sub20Device_list.end(); iterat++ ) 00193 { 00194 //verify if the sub20 device is configured (which should be the case as only configured sub20ies are pushed on list) 00195 if( iterat->bSubSPIConfigured == true ) 00196 { 00197 //Trace through cluster 00198 for( iChipSelect = 0; iChipSelect < smi540_cmd::MAX_SENSORS; iChipSelect++ ) 00199 { 00200 //verify if sensor is available on respective chipselect 00201 if( iterat->Smi540Cluster[iChipSelect].bConfigured == true ) 00202 { 00203 spi_error_code = 0; 00204 // SS_N iChipSelect; 00205 // SS_LO SS goes low and stays low during entire transfer, after that it goes high 00206 spi_error_code += sub_spi_transfer( iterat->handle_subdev, smi540_cmd::chRD_ACT_DATA_64, 0, 4, SS_CONF(iChipSelect,SS_LO) ); 00207 if( spi_error_code != 0 ) 00208 { 00209 ROS_WARN("SPI transfer result: %d\tCS: %d, ", spi_error_code, iChipSelect); 00210 } 00211 spi_error_code += sub_spi_transfer( iterat->handle_subdev, 0, chMM5_rx, 8, SS_CONF(iChipSelect,SS_LO) ); 00212 //ensure CS is high 00213 //spi_error_code += sub_spi_transfer( iterat->handle_subdev, 0, &chCMD, 1, SS_CONF(iChipSelect,SS_H) ); 00214 if( spi_error_code == 0 ) 00215 { 00216 SPIMeas = true; 00217 //Convert the response into scaled sensor measurements 00218 dRateZ = mm5data_to_double(chMM5_rx[5], chMM5_rx[6], smi540_cmd::eGYRO); 00219 dAccX = mm5data_to_double(chMM5_rx[3], chMM5_rx[4], smi540_cmd::eACCEL); 00220 dAccY = mm5data_to_double(chMM5_rx[1], chMM5_rx[2], smi540_cmd::eACCEL); 00221 00222 // collect the data for all available chipselects 00223 sMeas.dAccX[j] = dAccX; 00224 sMeas.dAccY[j] = dAccY; 00225 sMeas.dRateZ[j] = dRateZ; 00226 sMeas.iChipSelect[j] = iChipSelect; 00227 j++; 00228 sMeas.iNumAccels = j; 00229 //Extract status of channels 00230 smi540health = (unsigned short)( chMM5_rx[0] & 0x23 ); 00231 } 00232 else 00233 { 00234 throw std::string ("SPI transfer error"); 00235 } 00236 } 00237 } 00238 } 00239 // only publish data once data for all available chipselects is collected 00240 if( SPIMeas ) 00241 { 00242 sMeas.dtomeas = ros::Time::now(); 00243 sMeas.bMeasAvailable = true; 00244 sMeas.strSerial = iterat->strSub20Serial; 00245 //Push measurement onto heap 00246 list_meas.push_back( sMeas ); 00247 } 00248 else 00249 { 00250 throw std::string ("SUB20 connected but no access rights given!"); 00251 } 00252 } 00253 } 00254 00255 double Smi540::mm5data_to_double( char chMSB, char chLSB, smi540_cmd::eSensorType eSensor ) 00256 { 00257 short s16int; //2 byte int to build message 00258 double dSensorMeas; //Scaled sensor measurement 00259 //verify if pos or neg 00260 if( (chMSB & 0x80) == 0 ) 00261 { 00262 //positive number 00263 s16int = (short) ((((unsigned short)chMSB)&0xFF)<<8) + (((unsigned short)chLSB)&0xFF); 00264 } 00265 else { 00266 //negative number 00267 //set MSB (sign) to zero and build 2 complement unsigned 00268 s16int = (short)(((((unsigned short)chMSB)&0x7F)<<8) + (((unsigned short)chLSB)&0xFF)-32768); 00269 } 00270 00271 //Convert data with the respective Scale Factor 00272 if( eSensor == smi540_cmd::eACCEL ) 00273 { 00274 dSensorMeas = ((double)s16int) / smi540_cmd::fSFACC_inv; 00275 } 00276 else 00277 { 00278 dSensorMeas = ((double)s16int) / smi540_cmd::fSFGYRO_inv; 00279 } 00280 return (dSensorMeas); 00281 } 00282 00283 void Smi540::confsens_on_sub20( OneSub20Config *pOneSub20Conf ) 00284 { 00285 int spi_error_code; //Error code for Sub20 API 00286 int iChipSelect; 00287 sub_handle handle_sub20; 00288 char chCMD[8]; 00289 00290 //retrieve handle for sub20 device 00291 handle_sub20 = pOneSub20Conf->handle_subdev; 00292 for( iChipSelect = 0; iChipSelect < smi540_cmd::MAX_SENSORS; iChipSelect++ ) 00293 { 00294 spi_error_code = 0; 00295 // Ensure CS is high 00296 spi_error_code += sub_spi_transfer( handle_sub20, 0, &chCMD[0], 1, SS_CONF(iChipSelect,SS_H) ); 00297 // SS_CONF(iChipSelect,SS_LO): 00298 // SS_N iChipSelect; 00299 // SS_LO SS goes low and stays low during entire transfer, after that it goes high 00300 spi_error_code += sub_spi_transfer( handle_sub20, smi540_cmd::chTRIGGER_RESET, 0, 4, SS_CONF(iChipSelect,SS_LO) ); 00301 spi_error_code += sub_spi_transfer( handle_sub20, 0, &chCMD[0], 1, SS_CONF(iChipSelect,SS_H) ); 00302 spi_error_code += sub_spi_transfer( handle_sub20, smi540_cmd::chRD_STATUS_A, 0, 4, SS_CONF(iChipSelect,SS_LO) ); 00303 spi_error_code += sub_spi_transfer( handle_sub20, 0, chCMD, 8, SS_CONF(iChipSelect,SS_LO) ); 00304 00305 // Check if a sensor is connected on the specified iChipSelect 00306 if( (spi_error_code == 0) && (strlen(chCMD)<=1) ) 00307 { 00308 ROS_INFO("-----------------------------------------"); 00309 ROS_INFO("SMI 540 - Chip Select %d", iChipSelect); 00310 ROS_INFO("CONFIGURED"); 00311 pOneSub20Conf->Smi540Cluster[iChipSelect].bConfigured = true; 00312 } else { 00313 ROS_INFO("-----------------------------------------"); 00314 ROS_INFO("SMI 540 - Chip Select %d", iChipSelect); 00315 ROS_INFO("NO SENSOR DETECTED"); 00316 pOneSub20Conf->Smi540Cluster[iChipSelect].bConfigured = false; 00317 } 00318 00319 } 00320 }; 00321 00322 // ---------- 00323 // -- MAIN -- 00324 // ---------- 00325 int main( int argc, char **argv ) 00326 { 00327 double dRate_Hz; 00328 std::string sSub20Serial; 00329 ros::init(argc, argv, "smi540"); 00330 ros::NodeHandle nh; 00331 ros::Publisher smi540_pub = nh.advertise<smi540::smi540meas>("smi540", 100); 00332 00333 if( nh.getParam("/smi540/rate_Hz", dRate_Hz ) == false ) 00334 { 00335 dRate_Hz = smi540_cmd::DEFAULT_RATE_Hz; 00336 }; 00337 if(nh.getParam("/smi540/sub20serial", sSub20Serial) == false ) 00338 { 00339 sSub20Serial = smi540_cmd::sSUB20SERIAL; 00340 }; 00341 00342 Smi540 smi540_attached(sSub20Serial); 00343 OneSmi540Meas sOneMeas; 00344 smi540::smi540meas msg; 00345 std::list<OneSmi540Meas>measurements_list; 00346 00347 ros::Rate loop_rate(dRate_Hz); 00348 00349 while( nh.ok() ) 00350 { 00351 //try to poll one measurement from sensor 00352 try 00353 { 00354 smi540_attached.GetMeasurements( measurements_list ); 00355 } 00356 catch ( std::string strType ) 00357 { 00358 ROS_WARN_STREAM("An exception occurred: " << strType); 00359 //std::exit(1); 00360 continue; 00361 } 00362 00363 while( !measurements_list.empty() ) 00364 { 00365 sOneMeas = measurements_list.back(); 00366 measurements_list.pop_back(); 00367 //only publish if a successful measurement was received 00368 if( sOneMeas.bMeasAvailable == true ) 00369 { 00370 msg.strIdSubDev = sOneMeas.strSerial; 00371 00372 // collect all available chipselect values into one message 00373 for( int i = 0; i < sOneMeas.iNumAccels; i++ ) 00374 { 00375 msg.iChipSelect.push_back( sOneMeas.iChipSelect[i] ); 00376 msg.fAcclX.push_back( sOneMeas.dAccX[i] ); 00377 msg.fAcclY.push_back( sOneMeas.dAccY[i] ); 00378 msg.fRateZ.push_back( sOneMeas.dRateZ[i] ); 00379 } 00380 msg.header.stamp = sOneMeas.dtomeas; 00381 smi540_pub.publish( msg ); // publish data in message 00382 00383 // clear the message values after publishing to avoid accumulation of further values on subsequent messages. 00384 msg.iChipSelect.clear(); 00385 msg.fAcclX.clear(); 00386 msg.fAcclY.clear(); 00387 msg.fRateZ.clear(); 00388 } 00389 } 00390 ros::spinOnce(); 00391 loop_rate.sleep(); 00392 } 00393 } 00394