git commit -m "first commit for v2"
This commit is contained in:
173
Devices/Packages/wit_wt901ble_reader/src/main.c
Executable file
173
Devices/Packages/wit_wt901ble_reader/src/main.c
Executable file
@@ -0,0 +1,173 @@
|
||||
#include "wit_wt901ble_reader/serial.h"
|
||||
#include "wit_wt901ble_reader/wit_c_sdk.h"
|
||||
#include "wit_wt901ble_reader/REG.h"
|
||||
#include <stdint.h>
|
||||
|
||||
|
||||
#define ACC_UPDATE 0x01
|
||||
#define GYRO_UPDATE 0x02
|
||||
#define ANGLE_UPDATE 0x04
|
||||
#define MAG_UPDATE 0x08
|
||||
#define READ_UPDATE 0x80
|
||||
|
||||
|
||||
static int fd, s_iCurBaud = 115200;
|
||||
static volatile char s_cDataUpdate = 0;
|
||||
|
||||
|
||||
const int c_uiBaud[] = {2400 , 4800 , 9600 , 19200 , 38400 , 57600 , 115200 , 230400 , 460800 , 921600};
|
||||
|
||||
|
||||
static void AutoScanSensor(char* dev);
|
||||
static void SensorDataUpdata(uint32_t uiReg, uint32_t uiRegNum);
|
||||
static void Delayms(uint16_t ucMs);
|
||||
|
||||
|
||||
int main(int argc,char* argv[]){
|
||||
|
||||
if(argc < 2)
|
||||
{
|
||||
printf("please input dev name\n");
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
if((fd = serial_open(argv[1] , 115200)<0))
|
||||
{
|
||||
printf("open %s fail\n", argv[1]);
|
||||
return 0;
|
||||
}
|
||||
else printf("open %s success\n", argv[1]);
|
||||
|
||||
|
||||
float fAcc[3], fGyro[3], fAngle[3];
|
||||
int i , ret;
|
||||
char cBuff[1];
|
||||
|
||||
WitInit(WIT_PROTOCOL_NORMAL, 0x50);
|
||||
WitRegisterCallBack(SensorDataUpdata);
|
||||
|
||||
printf("\r\n********************** wit-motion Normal example ************************\r\n");
|
||||
AutoScanSensor(argv[1]);
|
||||
|
||||
while(1)
|
||||
{
|
||||
|
||||
while(serial_read_data(fd, cBuff, 1))
|
||||
{
|
||||
WitSerialDataIn(cBuff[0]);
|
||||
}
|
||||
printf("\n");
|
||||
Delayms(500);
|
||||
|
||||
if(s_cDataUpdate)
|
||||
{
|
||||
for(i = 0; i < 3; i++)
|
||||
{
|
||||
fAcc[i] = sReg[AX+i] / 32768.0f * 16.0f;
|
||||
fGyro[i] = sReg[GX+i] / 32768.0f * 2000.0f;
|
||||
fAngle[i] = sReg[Roll+i] / 32768.0f * 180.0f;
|
||||
}
|
||||
|
||||
if(s_cDataUpdate & ACC_UPDATE)
|
||||
{
|
||||
printf("acc:%.3f %.3f %.3f\r\n", fAcc[0], fAcc[1], fAcc[2]);
|
||||
s_cDataUpdate &= ~ACC_UPDATE;
|
||||
}
|
||||
if(s_cDataUpdate & GYRO_UPDATE)
|
||||
{
|
||||
printf("gyro:%.3f %.3f %.3f\r\n", fGyro[0], fGyro[1], fGyro[2]);
|
||||
s_cDataUpdate &= ~GYRO_UPDATE;
|
||||
}
|
||||
if(s_cDataUpdate & ANGLE_UPDATE)
|
||||
{
|
||||
printf("angle:%.3f %.3f %.3f\r\n", fAngle[0], fAngle[1], fAngle[2]);
|
||||
s_cDataUpdate &= ~ANGLE_UPDATE;
|
||||
}
|
||||
if(s_cDataUpdate & MAG_UPDATE)
|
||||
{
|
||||
printf("mag:%d %d %d\r\n", sReg[HX], sReg[HY], sReg[HZ]);
|
||||
s_cDataUpdate &= ~MAG_UPDATE;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
serial_close(fd);
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
static void SensorDataUpdata(uint32_t uiReg, uint32_t uiRegNum)
|
||||
{
|
||||
int i;
|
||||
for(i = 0; i < uiRegNum; i++)
|
||||
{
|
||||
switch(uiReg)
|
||||
{
|
||||
// case AX:
|
||||
// case AY:
|
||||
case AZ:
|
||||
s_cDataUpdate |= ACC_UPDATE;
|
||||
break;
|
||||
// case GX:
|
||||
// case GY:
|
||||
case GZ:
|
||||
s_cDataUpdate |= GYRO_UPDATE;
|
||||
break;
|
||||
// case HX:
|
||||
// case HY:
|
||||
case HZ:
|
||||
s_cDataUpdate |= MAG_UPDATE;
|
||||
break;
|
||||
// case Roll:
|
||||
// case Pitch:
|
||||
case Yaw:
|
||||
s_cDataUpdate |= ANGLE_UPDATE;
|
||||
break;
|
||||
default:
|
||||
s_cDataUpdate |= READ_UPDATE;
|
||||
break;
|
||||
}
|
||||
uiReg++;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static void Delayms(uint16_t ucMs)
|
||||
{
|
||||
usleep(ucMs*1000);
|
||||
}
|
||||
|
||||
|
||||
static void AutoScanSensor(char* dev)
|
||||
{
|
||||
int i, iRetry;
|
||||
char cBuff[1];
|
||||
|
||||
for(i = 1; i < 10; i++)
|
||||
{
|
||||
serial_close(fd);
|
||||
s_iCurBaud = c_uiBaud[i];
|
||||
fd = serial_open(dev , c_uiBaud[i]);
|
||||
|
||||
iRetry = 2;
|
||||
do
|
||||
{
|
||||
s_cDataUpdate = 0;
|
||||
WitReadReg(AX, 3);
|
||||
Delayms(200);
|
||||
while(serial_read_data(fd, cBuff, 1))
|
||||
{
|
||||
WitSerialDataIn(cBuff[0]);
|
||||
}
|
||||
if(s_cDataUpdate != 0)
|
||||
{
|
||||
printf("%d baud find sensor\r\n\r\n", c_uiBaud[i]);
|
||||
return ;
|
||||
}
|
||||
iRetry--;
|
||||
}while(iRetry);
|
||||
}
|
||||
printf("can not find sensor\r\n");
|
||||
printf("please check your connection\r\n");
|
||||
}
|
||||
100
Devices/Packages/wit_wt901ble_reader/src/serial.c
Executable file
100
Devices/Packages/wit_wt901ble_reader/src/serial.c
Executable file
@@ -0,0 +1,100 @@
|
||||
#include "wit_wt901ble_reader/serial.h"
|
||||
|
||||
|
||||
int serial_open(unsigned char* dev, unsigned int baud)
|
||||
{
|
||||
int fd;
|
||||
fd = open(dev, O_RDWR|O_NOCTTY);
|
||||
if (fd < 0) return fd;
|
||||
if(isatty(STDIN_FILENO)==0)
|
||||
{
|
||||
printf("standard input is not a terminal device\n");
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("isatty success!\n");
|
||||
}
|
||||
|
||||
struct termios newtio,oldtio;
|
||||
if (tcgetattr( fd,&oldtio) != 0)
|
||||
{
|
||||
perror("SetupSerial 1");
|
||||
printf("tcgetattr( fd,&oldtio) -> %d\n",tcgetattr( fd,&oldtio));
|
||||
return -1;
|
||||
}
|
||||
bzero( &newtio, sizeof( newtio ) );
|
||||
newtio.c_cflag |= CLOCAL | CREAD;
|
||||
newtio.c_cflag |= CS8;
|
||||
newtio.c_cflag &= ~PARENB;
|
||||
|
||||
/*设置波特率*/
|
||||
switch( baud )
|
||||
{
|
||||
case 2400:
|
||||
cfsetispeed(&newtio, B2400);
|
||||
cfsetospeed(&newtio, B2400);
|
||||
break;
|
||||
case 4800:
|
||||
cfsetispeed(&newtio, B4800);
|
||||
cfsetospeed(&newtio, B4800);
|
||||
break;
|
||||
case 9600:
|
||||
cfsetispeed(&newtio, B9600);
|
||||
cfsetospeed(&newtio, B9600);
|
||||
break;
|
||||
case 115200:
|
||||
cfsetispeed(&newtio, B115200);
|
||||
cfsetospeed(&newtio, B115200);
|
||||
break;
|
||||
case 230400:
|
||||
cfsetispeed(&newtio, B230400);
|
||||
cfsetospeed(&newtio, B230400);
|
||||
break;
|
||||
case 460800:
|
||||
cfsetispeed(&newtio, B460800);
|
||||
cfsetospeed(&newtio, B460800);
|
||||
break;
|
||||
default:
|
||||
cfsetispeed(&newtio, B9600);
|
||||
cfsetospeed(&newtio, B9600);
|
||||
break;
|
||||
}
|
||||
newtio.c_cflag &= ~CSTOPB;
|
||||
newtio.c_cc[VTIME] = 0;
|
||||
newtio.c_cc[VMIN] = 0;
|
||||
tcflush(fd,TCIFLUSH);
|
||||
|
||||
if((tcsetattr(fd,TCSANOW,&newtio))!=0)
|
||||
{
|
||||
perror("com set error");
|
||||
return -1;
|
||||
}
|
||||
|
||||
return fd;
|
||||
}
|
||||
|
||||
void serial_close(int fd)
|
||||
{
|
||||
close(fd);
|
||||
}
|
||||
|
||||
int serial_read_data(int fd, unsigned char *val, int len)
|
||||
{
|
||||
|
||||
len=read(fd,val,len);
|
||||
return len;
|
||||
|
||||
}
|
||||
|
||||
int serial_write_data(int fd, unsigned char *val, int len)
|
||||
{
|
||||
len=write(fd,val,len*sizeof(unsigned char));
|
||||
return len;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
502
Devices/Packages/wit_wt901ble_reader/src/wit_c_sdk.c
Executable file
502
Devices/Packages/wit_wt901ble_reader/src/wit_c_sdk.c
Executable file
@@ -0,0 +1,502 @@
|
||||
#include "wit_wt901ble_reader/wit_c_sdk.h"
|
||||
|
||||
static SerialWrite p_WitSerialWriteFunc = NULL;
|
||||
static WitI2cWrite p_WitI2cWriteFunc = NULL;
|
||||
static WitI2cRead p_WitI2cReadFunc = NULL;
|
||||
static CanWrite p_WitCanWriteFunc = NULL;
|
||||
static RegUpdateCb p_WitRegUpdateCbFunc = NULL;
|
||||
static DelaymsCb p_WitDelaymsFunc = NULL;
|
||||
|
||||
static uint8_t s_ucAddr = 0xff;
|
||||
static uint8_t s_ucWitDataBuff[WIT_DATA_BUFF_SIZE];
|
||||
static uint32_t s_uiWitDataCnt = 0, s_uiProtoclo = 0, s_uiReadRegIndex = 0;
|
||||
int16_t sReg[REGSIZE];
|
||||
|
||||
|
||||
#define FuncW 0x06
|
||||
#define FuncR 0x03
|
||||
|
||||
static const uint8_t __auchCRCHi[256] = {
|
||||
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81,
|
||||
0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
|
||||
0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01,
|
||||
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
|
||||
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81,
|
||||
0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0,
|
||||
0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01,
|
||||
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
|
||||
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81,
|
||||
0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
|
||||
0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01,
|
||||
0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
|
||||
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81,
|
||||
0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
|
||||
0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01,
|
||||
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
|
||||
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81,
|
||||
0x40
|
||||
};
|
||||
static const uint8_t __auchCRCLo[256] = {
|
||||
0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06, 0x07, 0xC7, 0x05, 0xC5, 0xC4,
|
||||
0x04, 0xCC, 0x0C, 0x0D, 0xCD, 0x0F, 0xCF, 0xCE, 0x0E, 0x0A, 0xCA, 0xCB, 0x0B, 0xC9, 0x09,
|
||||
0x08, 0xC8, 0xD8, 0x18, 0x19, 0xD9, 0x1B, 0xDB, 0xDA, 0x1A, 0x1E, 0xDE, 0xDF, 0x1F, 0xDD,
|
||||
0x1D, 0x1C, 0xDC, 0x14, 0xD4, 0xD5, 0x15, 0xD7, 0x17, 0x16, 0xD6, 0xD2, 0x12, 0x13, 0xD3,
|
||||
0x11, 0xD1, 0xD0, 0x10, 0xF0, 0x30, 0x31, 0xF1, 0x33, 0xF3, 0xF2, 0x32, 0x36, 0xF6, 0xF7,
|
||||
0x37, 0xF5, 0x35, 0x34, 0xF4, 0x3C, 0xFC, 0xFD, 0x3D, 0xFF, 0x3F, 0x3E, 0xFE, 0xFA, 0x3A,
|
||||
0x3B, 0xFB, 0x39, 0xF9, 0xF8, 0x38, 0x28, 0xE8, 0xE9, 0x29, 0xEB, 0x2B, 0x2A, 0xEA, 0xEE,
|
||||
0x2E, 0x2F, 0xEF, 0x2D, 0xED, 0xEC, 0x2C, 0xE4, 0x24, 0x25, 0xE5, 0x27, 0xE7, 0xE6, 0x26,
|
||||
0x22, 0xE2, 0xE3, 0x23, 0xE1, 0x21, 0x20, 0xE0, 0xA0, 0x60, 0x61, 0xA1, 0x63, 0xA3, 0xA2,
|
||||
0x62, 0x66, 0xA6, 0xA7, 0x67, 0xA5, 0x65, 0x64, 0xA4, 0x6C, 0xAC, 0xAD, 0x6D, 0xAF, 0x6F,
|
||||
0x6E, 0xAE, 0xAA, 0x6A, 0x6B, 0xAB, 0x69, 0xA9, 0xA8, 0x68, 0x78, 0xB8, 0xB9, 0x79, 0xBB,
|
||||
0x7B, 0x7A, 0xBA, 0xBE, 0x7E, 0x7F, 0xBF, 0x7D, 0xBD, 0xBC, 0x7C, 0xB4, 0x74, 0x75, 0xB5,
|
||||
0x77, 0xB7, 0xB6, 0x76, 0x72, 0xB2, 0xB3, 0x73, 0xB1, 0x71, 0x70, 0xB0, 0x50, 0x90, 0x91,
|
||||
0x51, 0x93, 0x53, 0x52, 0x92, 0x96, 0x56, 0x57, 0x97, 0x55, 0x95, 0x94, 0x54, 0x9C, 0x5C,
|
||||
0x5D, 0x9D, 0x5F, 0x9F, 0x9E, 0x5E, 0x5A, 0x9A, 0x9B, 0x5B, 0x99, 0x59, 0x58, 0x98, 0x88,
|
||||
0x48, 0x49, 0x89, 0x4B, 0x8B, 0x8A, 0x4A, 0x4E, 0x8E, 0x8F, 0x4F, 0x8D, 0x4D, 0x4C, 0x8C,
|
||||
0x44, 0x84, 0x85, 0x45, 0x87, 0x47, 0x46, 0x86, 0x82, 0x42, 0x43, 0x83, 0x41, 0x81, 0x80,
|
||||
0x40
|
||||
};
|
||||
|
||||
|
||||
static uint16_t __CRC16(uint8_t *puchMsg, uint16_t usDataLen)
|
||||
{
|
||||
uint8_t uchCRCHi = 0xFF;
|
||||
uint8_t uchCRCLo = 0xFF;
|
||||
uint8_t uIndex;
|
||||
int i = 0;
|
||||
uchCRCHi = 0xFF;
|
||||
uchCRCLo = 0xFF;
|
||||
for (; i<usDataLen; i++)
|
||||
{
|
||||
uIndex = uchCRCHi ^ puchMsg[i];
|
||||
uchCRCHi = uchCRCLo ^ __auchCRCHi[uIndex];
|
||||
uchCRCLo = __auchCRCLo[uIndex] ;
|
||||
}
|
||||
return (uint16_t)(((uint16_t)uchCRCHi << 8) | (uint16_t)uchCRCLo) ;
|
||||
}
|
||||
static uint8_t __CaliSum(uint8_t *data, uint32_t len)
|
||||
{
|
||||
uint32_t i;
|
||||
uint8_t ucCheck = 0;
|
||||
for(i=0; i<len; i++) ucCheck += *(data + i);
|
||||
return ucCheck;
|
||||
}
|
||||
int32_t WitSerialWriteRegister(SerialWrite Write_func)
|
||||
{
|
||||
if(!Write_func)return WIT_HAL_INVAL;
|
||||
p_WitSerialWriteFunc = Write_func;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
static void CopeWitData(uint8_t ucIndex, uint16_t *p_data, uint32_t uiLen)
|
||||
{
|
||||
uint32_t uiReg1 = 0, uiReg2 = 0, uiReg1Len = 0, uiReg2Len = 0;
|
||||
uint16_t *p_usReg1Val = p_data;
|
||||
uint16_t *p_usReg2Val = p_data+3;
|
||||
|
||||
uiReg1Len = 4;
|
||||
switch(ucIndex)
|
||||
{
|
||||
case WIT_ACC: uiReg1 = AX; uiReg1Len = 3; uiReg2 = TEMP; uiReg2Len = 1; break;
|
||||
case WIT_ANGLE: uiReg1 = Roll; uiReg1Len = 3; uiReg2 = VERSION; uiReg2Len = 1; break;
|
||||
case WIT_TIME: uiReg1 = YYMM; break;
|
||||
case WIT_GYRO: uiReg1 = GX; uiLen = 3;break;
|
||||
case WIT_MAGNETIC: uiReg1 = HX; uiLen = 3;break;
|
||||
case WIT_DPORT: uiReg1 = D0Status; break;
|
||||
case WIT_PRESS: uiReg1 = PressureL; break;
|
||||
case WIT_GPS: uiReg1 = LonL; break;
|
||||
case WIT_VELOCITY: uiReg1 = GPSHeight; break;
|
||||
case WIT_QUATER: uiReg1 = q0; break;
|
||||
case WIT_GSA: uiReg1 = SVNUM; break;
|
||||
case WIT_REGVALUE: uiReg1 = s_uiReadRegIndex; break;
|
||||
default:
|
||||
return ;
|
||||
|
||||
}
|
||||
if(uiLen == 3)
|
||||
{
|
||||
uiReg1Len = 3;
|
||||
uiReg2Len = 0;
|
||||
}
|
||||
if(uiReg1Len)
|
||||
{
|
||||
memcpy(&sReg[uiReg1], p_usReg1Val, uiReg1Len<<1);
|
||||
p_WitRegUpdateCbFunc(uiReg1, uiReg1Len);
|
||||
}
|
||||
if(uiReg2Len)
|
||||
{
|
||||
memcpy(&sReg[uiReg2], p_usReg2Val, uiReg2Len<<1);
|
||||
p_WitRegUpdateCbFunc(uiReg2, uiReg2Len);
|
||||
}
|
||||
}
|
||||
|
||||
void WitSerialDataIn(uint8_t ucData)
|
||||
{
|
||||
uint16_t usCRC16, usTemp, i, usData[4];
|
||||
uint8_t ucSum;
|
||||
|
||||
if(p_WitRegUpdateCbFunc == NULL)return ;
|
||||
s_ucWitDataBuff[s_uiWitDataCnt++] = ucData;
|
||||
switch(s_uiProtoclo)
|
||||
{
|
||||
case WIT_PROTOCOL_NORMAL:
|
||||
if(s_ucWitDataBuff[0] != 0x55)
|
||||
{
|
||||
s_uiWitDataCnt--;
|
||||
memcpy(s_ucWitDataBuff, &s_ucWitDataBuff[1], s_uiWitDataCnt);
|
||||
return ;
|
||||
}
|
||||
if(s_uiWitDataCnt >= 11)
|
||||
{
|
||||
ucSum = __CaliSum(s_ucWitDataBuff, 10);
|
||||
if(ucSum != s_ucWitDataBuff[10])
|
||||
{
|
||||
s_uiWitDataCnt--;
|
||||
memcpy(s_ucWitDataBuff, &s_ucWitDataBuff[1], s_uiWitDataCnt);
|
||||
return ;
|
||||
}
|
||||
usData[0] = ((uint16_t)s_ucWitDataBuff[3] << 8) | (uint16_t)s_ucWitDataBuff[2];
|
||||
usData[1] = ((uint16_t)s_ucWitDataBuff[5] << 8) | (uint16_t)s_ucWitDataBuff[4];
|
||||
usData[2] = ((uint16_t)s_ucWitDataBuff[7] << 8) | (uint16_t)s_ucWitDataBuff[6];
|
||||
usData[3] = ((uint16_t)s_ucWitDataBuff[9] << 8) | (uint16_t)s_ucWitDataBuff[8];
|
||||
CopeWitData(s_ucWitDataBuff[1], usData, 4);
|
||||
s_uiWitDataCnt = 0;
|
||||
}
|
||||
break;
|
||||
case WIT_PROTOCOL_MODBUS:
|
||||
if(s_uiWitDataCnt > 2)
|
||||
{
|
||||
if(s_ucWitDataBuff[1] != FuncR)
|
||||
{
|
||||
s_uiWitDataCnt--;
|
||||
memcpy(s_ucWitDataBuff, &s_ucWitDataBuff[1], s_uiWitDataCnt);
|
||||
return ;
|
||||
}
|
||||
if(s_uiWitDataCnt < (s_ucWitDataBuff[2] + 5))return ;
|
||||
usTemp = ((uint16_t)s_ucWitDataBuff[s_uiWitDataCnt-2] << 8) | s_ucWitDataBuff[s_uiWitDataCnt-1];
|
||||
usCRC16 = __CRC16(s_ucWitDataBuff, s_uiWitDataCnt-2);
|
||||
if(usTemp != usCRC16)
|
||||
{
|
||||
s_uiWitDataCnt--;
|
||||
memcpy(s_ucWitDataBuff, &s_ucWitDataBuff[1], s_uiWitDataCnt);
|
||||
return ;
|
||||
}
|
||||
usTemp = s_ucWitDataBuff[2] >> 1;
|
||||
for(i = 0; i < usTemp; i++)
|
||||
{
|
||||
sReg[i+s_uiReadRegIndex] = ((uint16_t)s_ucWitDataBuff[(i<<1)+3] << 8) | s_ucWitDataBuff[(i<<1)+4];
|
||||
}
|
||||
p_WitRegUpdateCbFunc(s_uiReadRegIndex, usTemp);
|
||||
s_uiWitDataCnt = 0;
|
||||
}
|
||||
break;
|
||||
case WIT_PROTOCOL_CAN:
|
||||
case WIT_PROTOCOL_I2C:
|
||||
s_uiWitDataCnt = 0;
|
||||
break;
|
||||
}
|
||||
if(s_uiWitDataCnt == WIT_DATA_BUFF_SIZE)s_uiWitDataCnt = 0;
|
||||
}
|
||||
int32_t WitI2cFuncRegister(WitI2cWrite write_func, WitI2cRead read_func)
|
||||
{
|
||||
if(!write_func)return WIT_HAL_INVAL;
|
||||
if(!read_func)return WIT_HAL_INVAL;
|
||||
p_WitI2cWriteFunc = write_func;
|
||||
p_WitI2cReadFunc = read_func;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
int32_t WitCanWriteRegister(CanWrite Write_func)
|
||||
{
|
||||
if(!Write_func)return WIT_HAL_INVAL;
|
||||
p_WitCanWriteFunc = Write_func;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
void WitCanDataIn(uint8_t ucData[8], uint8_t ucLen)
|
||||
{
|
||||
uint16_t usData[3];
|
||||
if(p_WitRegUpdateCbFunc == NULL)return ;
|
||||
if(ucLen < 8)return ;
|
||||
switch(s_uiProtoclo)
|
||||
{
|
||||
case WIT_PROTOCOL_CAN:
|
||||
if(ucData[0] != 0x55)return ;
|
||||
usData[0] = ((uint16_t)ucData[3] << 8) | ucData[2];
|
||||
usData[1] = ((uint16_t)ucData[5] << 8) | ucData[4];
|
||||
usData[2] = ((uint16_t)ucData[7] << 8) | ucData[6];
|
||||
CopeWitData(ucData[1], usData, 3);
|
||||
break;
|
||||
case WIT_PROTOCOL_NORMAL:
|
||||
case WIT_PROTOCOL_MODBUS:
|
||||
case WIT_PROTOCOL_I2C:
|
||||
break;
|
||||
}
|
||||
}
|
||||
int32_t WitRegisterCallBack(RegUpdateCb update_func)
|
||||
{
|
||||
if(!update_func)return WIT_HAL_INVAL;
|
||||
p_WitRegUpdateCbFunc = update_func;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
int32_t WitWriteReg(uint32_t uiReg, uint16_t usData)
|
||||
{
|
||||
uint16_t usCRC;
|
||||
uint8_t ucBuff[8];
|
||||
if(uiReg >= REGSIZE)return WIT_HAL_INVAL;
|
||||
switch(s_uiProtoclo)
|
||||
{
|
||||
case WIT_PROTOCOL_NORMAL:
|
||||
if(p_WitSerialWriteFunc == NULL)return WIT_HAL_EMPTY;
|
||||
ucBuff[0] = 0xFF;
|
||||
ucBuff[1] = 0xAA;
|
||||
ucBuff[2] = uiReg & 0xFF;
|
||||
ucBuff[3] = usData & 0xff;
|
||||
ucBuff[4] = usData >> 8;
|
||||
p_WitSerialWriteFunc(ucBuff, 5);
|
||||
break;
|
||||
case WIT_PROTOCOL_MODBUS:
|
||||
if(p_WitSerialWriteFunc == NULL)return WIT_HAL_EMPTY;
|
||||
ucBuff[0] = s_ucAddr;
|
||||
ucBuff[1] = FuncW;
|
||||
ucBuff[2] = uiReg >> 8;
|
||||
ucBuff[3] = uiReg & 0xFF;
|
||||
ucBuff[4] = usData >> 8;
|
||||
ucBuff[5] = usData & 0xff;
|
||||
usCRC = __CRC16(ucBuff, 6);
|
||||
ucBuff[6] = usCRC >> 8;
|
||||
ucBuff[7] = usCRC & 0xff;
|
||||
p_WitSerialWriteFunc(ucBuff, 8);
|
||||
break;
|
||||
case WIT_PROTOCOL_CAN:
|
||||
if(p_WitCanWriteFunc == NULL)return WIT_HAL_EMPTY;
|
||||
ucBuff[0] = 0xFF;
|
||||
ucBuff[1] = 0xAA;
|
||||
ucBuff[2] = uiReg & 0xFF;
|
||||
ucBuff[3] = usData & 0xff;
|
||||
ucBuff[4] = usData >> 8;
|
||||
p_WitCanWriteFunc(s_ucAddr, ucBuff, 5);
|
||||
break;
|
||||
case WIT_PROTOCOL_I2C:
|
||||
if(p_WitI2cWriteFunc == NULL)return WIT_HAL_EMPTY;
|
||||
ucBuff[0] = usData & 0xff;
|
||||
ucBuff[1] = usData >> 8;
|
||||
if(p_WitI2cWriteFunc(s_ucAddr << 1, uiReg, ucBuff, 2) != 1)
|
||||
{
|
||||
//printf("i2c write fail\r\n");
|
||||
}
|
||||
break;
|
||||
default:
|
||||
return WIT_HAL_INVAL;
|
||||
}
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
int32_t WitReadReg(uint32_t uiReg, uint32_t uiReadNum)
|
||||
{
|
||||
uint16_t usTemp, i;
|
||||
uint8_t ucBuff[8];
|
||||
if((uiReg + uiReadNum) >= REGSIZE)return WIT_HAL_INVAL;
|
||||
switch(s_uiProtoclo)
|
||||
{
|
||||
case WIT_PROTOCOL_NORMAL:
|
||||
if(uiReadNum > 4)return WIT_HAL_INVAL;
|
||||
if(p_WitSerialWriteFunc == NULL)return WIT_HAL_EMPTY;
|
||||
ucBuff[0] = 0xFF;
|
||||
ucBuff[1] = 0xAA;
|
||||
ucBuff[2] = 0x27;
|
||||
ucBuff[3] = uiReg & 0xff;
|
||||
ucBuff[4] = uiReg >> 8;
|
||||
p_WitSerialWriteFunc(ucBuff, 5);
|
||||
break;
|
||||
case WIT_PROTOCOL_MODBUS:
|
||||
if(p_WitSerialWriteFunc == NULL)return WIT_HAL_EMPTY;
|
||||
usTemp = uiReadNum << 1;
|
||||
if((usTemp + 5) > WIT_DATA_BUFF_SIZE)return WIT_HAL_NOMEM;
|
||||
ucBuff[0] = s_ucAddr;
|
||||
ucBuff[1] = FuncR;
|
||||
ucBuff[2] = uiReg >> 8;
|
||||
ucBuff[3] = uiReg & 0xFF;
|
||||
ucBuff[4] = uiReadNum >> 8;
|
||||
ucBuff[5] = uiReadNum & 0xff;
|
||||
usTemp = __CRC16(ucBuff, 6);
|
||||
ucBuff[6] = usTemp >> 8;
|
||||
ucBuff[7] = usTemp & 0xff;
|
||||
p_WitSerialWriteFunc(ucBuff, 8);
|
||||
break;
|
||||
case WIT_PROTOCOL_CAN:
|
||||
if(uiReadNum > 3)return WIT_HAL_INVAL;
|
||||
if(p_WitCanWriteFunc == NULL)return WIT_HAL_EMPTY;
|
||||
ucBuff[0] = 0xFF;
|
||||
ucBuff[1] = 0xAA;
|
||||
ucBuff[2] = 0x27;
|
||||
ucBuff[3] = uiReg & 0xff;
|
||||
ucBuff[4] = uiReg >> 8;
|
||||
p_WitCanWriteFunc(s_ucAddr, ucBuff, 5);
|
||||
break;
|
||||
case WIT_PROTOCOL_I2C:
|
||||
if(p_WitI2cReadFunc == NULL)return WIT_HAL_EMPTY;
|
||||
usTemp = uiReadNum << 1;
|
||||
if(WIT_DATA_BUFF_SIZE < usTemp)return WIT_HAL_NOMEM;
|
||||
if(p_WitI2cReadFunc(s_ucAddr << 1, uiReg, s_ucWitDataBuff, usTemp) == 1)
|
||||
{
|
||||
if(p_WitRegUpdateCbFunc == NULL)return WIT_HAL_EMPTY;
|
||||
for(i = 0; i < uiReadNum; i++)
|
||||
{
|
||||
sReg[i+uiReg] = ((uint16_t)s_ucWitDataBuff[(i<<1)+1] << 8) | s_ucWitDataBuff[i<<1];
|
||||
}
|
||||
p_WitRegUpdateCbFunc(uiReg, uiReadNum);
|
||||
}
|
||||
|
||||
break;
|
||||
default:
|
||||
return WIT_HAL_INVAL;
|
||||
}
|
||||
s_uiReadRegIndex = uiReg;
|
||||
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
int32_t WitInit(uint32_t uiProtocol, uint8_t ucAddr)
|
||||
{
|
||||
if(uiProtocol > WIT_PROTOCOL_I2C)return WIT_HAL_INVAL;
|
||||
s_uiProtoclo = uiProtocol;
|
||||
s_ucAddr = ucAddr;
|
||||
s_uiWitDataCnt = 0;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
void WitDeInit(void)
|
||||
{
|
||||
p_WitSerialWriteFunc = NULL;
|
||||
p_WitI2cWriteFunc = NULL;
|
||||
p_WitI2cReadFunc = NULL;
|
||||
p_WitCanWriteFunc = NULL;
|
||||
p_WitRegUpdateCbFunc = NULL;
|
||||
s_ucAddr = 0xff;
|
||||
s_uiWitDataCnt = 0;
|
||||
s_uiProtoclo = 0;
|
||||
}
|
||||
|
||||
int32_t WitDelayMsRegister(DelaymsCb delayms_func)
|
||||
{
|
||||
if(!delayms_func)return WIT_HAL_INVAL;
|
||||
p_WitDelaymsFunc = delayms_func;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
|
||||
char CheckRange(short sTemp,short sMin,short sMax)
|
||||
{
|
||||
if ((sTemp>=sMin)&&(sTemp<=sMax)) return 1;
|
||||
else return 0;
|
||||
}
|
||||
/*Acceleration calibration demo*/
|
||||
int32_t WitStartAccCali(void)
|
||||
{
|
||||
/*
|
||||
First place the equipment horizontally, and then perform the following operations
|
||||
*/
|
||||
if(WitWriteReg(KEY, KEY_UNLOCK) != WIT_HAL_OK) return WIT_HAL_ERROR;// unlock reg
|
||||
if(s_uiProtoclo == WIT_PROTOCOL_MODBUS) p_WitDelaymsFunc(20);
|
||||
else if(s_uiProtoclo == WIT_PROTOCOL_NORMAL) p_WitDelaymsFunc(1);
|
||||
else ;
|
||||
if(WitWriteReg(CALSW, CALGYROACC) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
int32_t WitStopAccCali(void)
|
||||
{
|
||||
if(WitWriteReg(CALSW, NORMAL) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
if(s_uiProtoclo == WIT_PROTOCOL_MODBUS) p_WitDelaymsFunc(20);
|
||||
else if(s_uiProtoclo == WIT_PROTOCOL_NORMAL) p_WitDelaymsFunc(1);
|
||||
else ;
|
||||
if(WitWriteReg(SAVE, SAVE_PARAM) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
/*Magnetic field calibration*/
|
||||
int32_t WitStartMagCali(void)
|
||||
{
|
||||
if(WitWriteReg(KEY, KEY_UNLOCK) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
if(s_uiProtoclo == WIT_PROTOCOL_MODBUS) p_WitDelaymsFunc(20);
|
||||
else if(s_uiProtoclo == WIT_PROTOCOL_NORMAL) p_WitDelaymsFunc(1);
|
||||
else ;
|
||||
if(WitWriteReg(CALSW, CALMAGMM) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
int32_t WitStopMagCali(void)
|
||||
{
|
||||
if(WitWriteReg(KEY, KEY_UNLOCK) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
if(s_uiProtoclo == WIT_PROTOCOL_MODBUS) p_WitDelaymsFunc(20);
|
||||
else if(s_uiProtoclo == WIT_PROTOCOL_NORMAL) p_WitDelaymsFunc(1);
|
||||
else ;
|
||||
if(WitWriteReg(CALSW, NORMAL) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
/*change Band*/
|
||||
int32_t WitSetUartBaud(int32_t uiBaudIndex)
|
||||
{
|
||||
if(!CheckRange(uiBaudIndex,WIT_BAUD_4800,WIT_BAUD_230400))
|
||||
{
|
||||
return WIT_HAL_INVAL;
|
||||
}
|
||||
if(WitWriteReg(KEY, KEY_UNLOCK) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
if(s_uiProtoclo == WIT_PROTOCOL_MODBUS) p_WitDelaymsFunc(20);
|
||||
else if(s_uiProtoclo == WIT_PROTOCOL_NORMAL) p_WitDelaymsFunc(1);
|
||||
else ;
|
||||
if(WitWriteReg(BAUD, uiBaudIndex) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
/*change Can Band*/
|
||||
int32_t WitSetCanBaud(int32_t uiBaudIndex)
|
||||
{
|
||||
if(!CheckRange(uiBaudIndex,CAN_BAUD_1000000,CAN_BAUD_3000))
|
||||
{
|
||||
return WIT_HAL_INVAL;
|
||||
}
|
||||
if(WitWriteReg(KEY, KEY_UNLOCK) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
if(s_uiProtoclo == WIT_PROTOCOL_MODBUS) p_WitDelaymsFunc(20);
|
||||
else if(s_uiProtoclo == WIT_PROTOCOL_NORMAL) p_WitDelaymsFunc(1);
|
||||
else ;
|
||||
if(WitWriteReg(BAUD, uiBaudIndex) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
/*change Bandwidth*/
|
||||
int32_t WitSetBandwidth(int32_t uiBaudWidth)
|
||||
{
|
||||
if(!CheckRange(uiBaudWidth,BANDWIDTH_256HZ,BANDWIDTH_5HZ))
|
||||
{
|
||||
return WIT_HAL_INVAL;
|
||||
}
|
||||
if(WitWriteReg(KEY, KEY_UNLOCK) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
if(s_uiProtoclo == WIT_PROTOCOL_MODBUS) p_WitDelaymsFunc(20);
|
||||
else if(s_uiProtoclo == WIT_PROTOCOL_NORMAL) p_WitDelaymsFunc(1);
|
||||
else ;
|
||||
if(WitWriteReg(BANDWIDTH, uiBaudWidth) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
|
||||
/*change output rate */
|
||||
int32_t WitSetOutputRate(int32_t uiRate)
|
||||
{
|
||||
if(!CheckRange(uiRate,RRATE_02HZ,RRATE_NONE))
|
||||
{
|
||||
return WIT_HAL_INVAL;
|
||||
}
|
||||
if(WitWriteReg(KEY, KEY_UNLOCK) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
if(s_uiProtoclo == WIT_PROTOCOL_MODBUS) p_WitDelaymsFunc(20);
|
||||
else if(s_uiProtoclo == WIT_PROTOCOL_NORMAL) p_WitDelaymsFunc(1);
|
||||
else ;
|
||||
if(WitWriteReg(RRATE, uiRate) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
|
||||
/*change WitSetContent */
|
||||
int32_t WitSetContent(int32_t uiRsw)
|
||||
{
|
||||
if(!CheckRange(uiRsw,RSW_TIME,RSW_MASK))
|
||||
{
|
||||
return WIT_HAL_INVAL;
|
||||
}
|
||||
if(WitWriteReg(KEY, KEY_UNLOCK) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
if(s_uiProtoclo == WIT_PROTOCOL_MODBUS) p_WitDelaymsFunc(20);
|
||||
else if(s_uiProtoclo == WIT_PROTOCOL_NORMAL) p_WitDelaymsFunc(1);
|
||||
else ;
|
||||
if(WitWriteReg(RSW, uiRsw) != WIT_HAL_OK) return WIT_HAL_ERROR;
|
||||
return WIT_HAL_OK;
|
||||
}
|
||||
|
||||
|
||||
|
||||
387
Devices/Packages/wit_wt901ble_reader/src/wit_wt901ble_reader.cc
Executable file
387
Devices/Packages/wit_wt901ble_reader/src/wit_wt901ble_reader.cc
Executable file
@@ -0,0 +1,387 @@
|
||||
#include "wit_wt901ble_reader/wit_wt901ble_reader.h"
|
||||
|
||||
namespace wt901ble_reader
|
||||
{
|
||||
|
||||
Diagnostics::Diagnostics(string& nodename):nodename_(nodename), nh_("~")
|
||||
{
|
||||
imu_diagnostics_topic_name_ = "";
|
||||
if(!ros::param::get(nodename_ + "/imu_diagnostics_topic_name", imu_diagnostics_topic_name_))
|
||||
{
|
||||
imu_diagnostics_topic_name_ = "/imu_diagnostics";
|
||||
ROS_WARN("Node: %s cannot get params", nodename_.c_str());
|
||||
}
|
||||
diagnostics_pub = nh_.advertise<diagnostic_msgs::DiagnosticArray>(imu_diagnostics_topic_name_, 10);
|
||||
diagnostics_thread = new boost::thread(&Diagnostics::run_diagnostics, this);
|
||||
}
|
||||
Diagnostics::~Diagnostics()
|
||||
{
|
||||
diagnostics_thread->join();
|
||||
delete(diagnostics_thread);
|
||||
}
|
||||
|
||||
void Diagnostics::run_diagnostics()
|
||||
{
|
||||
ros::Duration(0.5).sleep();
|
||||
connection.name = "connection";
|
||||
connection.hardware_id = "IMU_sensors";
|
||||
connection.level = connection.STALE;
|
||||
connection.message = "Initialized";
|
||||
pubDiagnostics();
|
||||
ros::Rate r(5);
|
||||
boost::lock_guard<boost::mutex> lock(mutex);
|
||||
while(ros::ok())
|
||||
{
|
||||
ros::spinOnce();
|
||||
if(!is_imu_connected)
|
||||
{
|
||||
connection.level = connection.ERROR;
|
||||
connection.message = "Cannot connect to device";
|
||||
}
|
||||
else{
|
||||
if(is_imu_data_available)
|
||||
{
|
||||
connection.level = connection.OK;
|
||||
connection.message = "Connected to device, datas is received";
|
||||
}
|
||||
else
|
||||
{
|
||||
connection.level = connection.WARN;
|
||||
connection.message = "Connected to device but datas is not received";
|
||||
}
|
||||
}
|
||||
pubDiagnostics();
|
||||
r.sleep();
|
||||
}
|
||||
}
|
||||
void Diagnostics::pubDiagnostics() {
|
||||
diagnostic_msgs::DiagnosticArray diagnostic;
|
||||
diagnostic.status.push_back(connection);
|
||||
if(diagnostic.status != prev_diagnostic.status)
|
||||
{
|
||||
diagnostic.header.seq = prev_diagnostic.header.seq+1;
|
||||
diagnostic.header.stamp = ros::Time::now();
|
||||
diagnostic.header.frame_id = "frame_id";
|
||||
diagnostics_pub.publish(diagnostic);
|
||||
prev_diagnostic = diagnostic;
|
||||
}
|
||||
}
|
||||
|
||||
wt901ble_node::wt901ble_node(const string& nodename):nodename_(nodename), nh_("~")
|
||||
{
|
||||
userParams = new UserParams();
|
||||
wt901ble_data_ = new wt901ble_data();
|
||||
if(LoadParams(userParams, nodename_)){
|
||||
ROS_INFO("%s : Params is loaded", nodename_.c_str());
|
||||
}
|
||||
else ROS_ERROR("%s : Fail to load params", nodename_.c_str());
|
||||
isDataAvailable = false;
|
||||
wt901ble_data_pub_ = nh_.advertise<sensor_msgs::Imu>(userParams->topic_name,10,false);
|
||||
isConnected_ = false;
|
||||
is_imu_connected = false;
|
||||
is_imu_data_available = false;
|
||||
is_try_to_connect = false;
|
||||
is_reconnected = false;
|
||||
lost_data_count = 0;
|
||||
reconnect_timer = nh_.createWallTimer(::ros::WallDuration(0.5), &wt901ble_node::ReconnectSerial, this);
|
||||
get_and_publish_timer = nh_.createWallTimer(::ros::WallDuration(0.02), &wt901ble_node::GetAndPublishData, this);
|
||||
reconnect_timer.stop();
|
||||
if(detect_port(userParams->portname))
|
||||
{
|
||||
ROS_INFO("Port: %s is found",userParams->portname.c_str());
|
||||
try {
|
||||
serial_ = new serial::Serial(userParams->portname, userParams->baudrate, serial::Timeout::simpleTimeout(500));
|
||||
}
|
||||
catch(const std::exception& ex)
|
||||
{
|
||||
isConnected_ = false;
|
||||
is_imu_connected = false;
|
||||
ROS_WARN("Can not open serial port: %s", userParams->portname.c_str());
|
||||
cerr << "Unhandled Exception: " << ex.what() << endl;
|
||||
}
|
||||
if(serial_!=NULL)
|
||||
{
|
||||
if(serial_-> isOpen()){
|
||||
ROS_INFO("%s: Connected to serial port: %s, baudrate: %d", nodename_.c_str(), userParams->portname.c_str(), userParams->baudrate);
|
||||
isConnected_ = true;
|
||||
is_imu_connected = true;
|
||||
}
|
||||
}
|
||||
get_and_publish_timer.start();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
wt901ble_node::~wt901ble_node()
|
||||
{
|
||||
delete(serial_);
|
||||
delete(userParams);
|
||||
delete(wt901ble_data_);
|
||||
}
|
||||
|
||||
void wt901ble_node::GetAndPublishData(const ::ros::WallTimerEvent& timer_event)
|
||||
{
|
||||
if(isConnected_)
|
||||
{
|
||||
if(recvData(data_buf))
|
||||
{
|
||||
// ROS_INFO_ONCE("%s: Start to get datas and publish", nodename_.c_str());
|
||||
// size_t data_buf_size = sizeof(data_buf)/sizeof(data_buf[0]);
|
||||
// int len = static_cast<int>(data_buf_size);
|
||||
// ROS_INFO("len: %d, data_buf: %x, %x, %x, %x, %x, %x, %x, %x, %x, %x, %x, %x, %x, %x, %x, %x, %x, %x, %x, %x",
|
||||
// len, data_buf[0], data_buf[1], data_buf[2], data_buf[3], data_buf[4], data_buf[5],
|
||||
// data_buf[6], data_buf[7], data_buf[8], data_buf[9], data_buf[10], data_buf[11],
|
||||
// data_buf[12], data_buf[13], data_buf[14], data_buf[15], data_buf[16], data_buf[17], data_buf[18], data_buf[19]);
|
||||
|
||||
int16_t aX = (data_buf[3]<<8U)|data_buf[2];
|
||||
int16_t aY = (data_buf[5]<<8U)|data_buf[4];
|
||||
int16_t aZ = (data_buf[7]<<8U)|data_buf[6];
|
||||
int16_t wX = (data_buf[9]<<8U)|data_buf[8];
|
||||
int16_t wY = (data_buf[11]<<8U)|data_buf[10];
|
||||
int16_t wZ = (data_buf[13]<<8U)|data_buf[12];
|
||||
int16_t Roll = (data_buf[15]<<8U)|data_buf[14];
|
||||
int16_t Pitch = (data_buf[17]<<8U)|data_buf[16];
|
||||
int16_t Yaw = (data_buf[19]<<8U)|data_buf[18];
|
||||
|
||||
wt901ble_data_->aX = ((double)(aX))/32768*156.9064;
|
||||
wt901ble_data_->aY = ((double)(aY))/32768*156.9064;
|
||||
wt901ble_data_->aZ = ((double)(aZ))/32768*156.9064;
|
||||
wt901ble_data_->wX = ((double)(wX))/32768*2000;
|
||||
wt901ble_data_->wY = ((double)(wY))/32768*2000;
|
||||
wt901ble_data_->wZ = ((double)(wZ))/32768*2000;
|
||||
wt901ble_data_->Roll = ((double)(Roll))/32768*180;
|
||||
wt901ble_data_->Pitch = ((double)(Pitch))/32768*180;
|
||||
wt901ble_data_->Yaw = ((double)(Yaw))/32768*180;
|
||||
|
||||
wt901ble_data_->wX = (wt901ble_data_->wX*M_PI)/180;
|
||||
wt901ble_data_->wY = (wt901ble_data_->wY*M_PI)/180;
|
||||
wt901ble_data_->wZ = (wt901ble_data_->wZ*M_PI)/180;
|
||||
|
||||
// ROS_INFO("Roll: %f, Pitch: %f, Yaw: %f",
|
||||
// wt901ble_data_->Roll, wt901ble_data_->Pitch, wt901ble_data_->Yaw);
|
||||
wt901ble_data_->Roll = (wt901ble_data_->Roll*M_PI)/180;
|
||||
wt901ble_data_->Pitch = (wt901ble_data_->Pitch*M_PI)/180;
|
||||
wt901ble_data_->Yaw = (wt901ble_data_->Yaw*M_PI)/180;
|
||||
|
||||
imu_data.header.frame_id = userParams->frame_id;
|
||||
imu_data.header.stamp = ros::Time::now();
|
||||
imu_data.orientation = getQuaternion(wt901ble_data_->Yaw, wt901ble_data_->Pitch, wt901ble_data_->Roll);
|
||||
// imu_data.orientation_covariance[0] = 2.8900000000000004e-08;
|
||||
// imu_data.orientation_covariance[4] = 2.8900000000000004e-08;
|
||||
// imu_data.orientation_covariance[8] = 2.8900000000000004e-08;
|
||||
imu_data.orientation_covariance[0] = 0.1;
|
||||
imu_data.orientation_covariance[4] = 0.1;
|
||||
imu_data.orientation_covariance[8] = 0.1;
|
||||
imu_data.angular_velocity.x = wt901ble_data_->wX;
|
||||
imu_data.angular_velocity.y = wt901ble_data_->wY;
|
||||
imu_data.angular_velocity.z = wt901ble_data_->wZ;
|
||||
// imu_data.angular_velocity_covariance[0] = 2.8900000000000004e-08;
|
||||
// imu_data.angular_velocity_covariance[4] = 2.8900000000000004e-08;
|
||||
// imu_data.angular_velocity_covariance[8] = 2.8900000000000004e-08;
|
||||
imu_data.angular_velocity_covariance[0] = 8e-6;
|
||||
imu_data.angular_velocity_covariance[4] = 8e-6;
|
||||
imu_data.angular_velocity_covariance[8] = 3e-7;
|
||||
imu_data.linear_acceleration.x = wt901ble_data_->aX;
|
||||
imu_data.linear_acceleration.y = wt901ble_data_->aY;
|
||||
imu_data.linear_acceleration.z = wt901ble_data_->aZ;
|
||||
// imu_data.linear_acceleration_covariance[0] = 0.009604000000000001;
|
||||
// imu_data.linear_acceleration_covariance[4] = 0.009604000000000001;
|
||||
// imu_data.linear_acceleration_covariance[8] = 0.009604000000000001;
|
||||
imu_data.linear_acceleration_covariance[0] = 5e-5;
|
||||
imu_data.linear_acceleration_covariance[4] = 0.0001;
|
||||
imu_data.linear_acceleration_covariance[8] = 0.00013;
|
||||
wt901ble_data_pub_.publish(imu_data);
|
||||
// ROS_INFO("Roll: %f, Pitch: %f, Yaw: %f",
|
||||
// wt901ble_data_->Roll, wt901ble_data_->Pitch, wt901ble_data_->Yaw);
|
||||
// ROS_INFO("aX: %f, aY: %f, aZ: %f, wX: %f, wY: %f, wZ: %f, Roll: %f, Pitch: %f, Yaw: %f",
|
||||
// wt901ble_data_->aX, wt901ble_data_->aY, wt901ble_data_->aZ,
|
||||
// wt901ble_data_->wX, wt901ble_data_->wY, wt901ble_data_->wZ,
|
||||
// wt901ble_data_->Roll, wt901ble_data_->Pitch, wt901ble_data_->Yaw);
|
||||
is_imu_data_available = true;
|
||||
lost_data_count = 0;
|
||||
is_try_to_connect = false;
|
||||
}
|
||||
else
|
||||
{
|
||||
lost_data_count ++;
|
||||
if(lost_data_count>30)
|
||||
{
|
||||
is_imu_data_available = false;
|
||||
if(is_try_to_connect ==false) { is_try_to_connect=true; reconnect_timer.start();}
|
||||
// ROS_WARN("IMU reader node: lost_data");
|
||||
lost_data_count = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void wt901ble_node::ReconnectSerial(const ::ros::WallTimerEvent& timer_event)
|
||||
{
|
||||
if(is_try_to_connect)
|
||||
{
|
||||
if(!is_reconnected)
|
||||
{
|
||||
if(serial_!=NULL)
|
||||
{
|
||||
isConnected_ = false;
|
||||
is_imu_connected = false;
|
||||
// boost::this_thread::sleep(boost::posix_time::milliseconds(500));
|
||||
ros::Duration(0.5).sleep();
|
||||
serial_->flush();
|
||||
serial_->close();
|
||||
delete(serial_);
|
||||
serial_ = new serial::Serial(userParams->portname, userParams->baudrate, serial::Timeout::simpleTimeout(500));
|
||||
}
|
||||
if(serial_!=NULL)
|
||||
{
|
||||
if(serial_-> isOpen()){
|
||||
ROS_WARN("%s: Reconnected to serial port (IMU sensor): %s, baudrate: %d", nodename_.c_str(), userParams->portname.c_str(), userParams->baudrate);
|
||||
isConnected_ = true;
|
||||
is_imu_connected = true;
|
||||
}
|
||||
}
|
||||
is_reconnected = true;
|
||||
reconnect_timer.stop();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
geometry_msgs::Quaternion wt901ble_node::getQuaternion(double yaw, double pitch, double roll)
|
||||
{
|
||||
double cy = cos(yaw * 0.5);
|
||||
double sy = sin(yaw * 0.5);
|
||||
double cp = cos(pitch * 0.5);
|
||||
double sp = sin(pitch * 0.5);
|
||||
double cr = cos(roll * 0.5);
|
||||
double sr = sin(roll * 0.5);
|
||||
geometry_msgs::Quaternion q;
|
||||
q.x = sr * cp * cy - cr * sp * sy;
|
||||
q.y = cr * sp * cy + sr * cp * sy;
|
||||
q.z = cr * cp * sy - sr * sp * cy;
|
||||
q.w = cr * cp * cy + sr * sp * sy;
|
||||
return q;
|
||||
}
|
||||
|
||||
bool wt901ble_node::LoadParams(UserParams* userParams_, const string& node_name){
|
||||
bool result = true;
|
||||
try{
|
||||
int baudrate;
|
||||
if(!ros::param::get(node_name + "/baudrate", baudrate)) result = false;
|
||||
if(!ros::param::get(node_name + "/portname", userParams_->portname)) result = false;
|
||||
if(!ros::param::get(node_name + "/topic_name", userParams_->topic_name)) result = false;
|
||||
if(!ros::param::get(node_name + "/frame_id", userParams_->frame_id)) result = false;
|
||||
userParams_->baudrate = static_cast<uint32_t>(baudrate);
|
||||
}
|
||||
catch(const std::exception& ex)
|
||||
{
|
||||
std::cerr << "Fail to load user params caught: " << ex.what() << std::endl;
|
||||
result = false;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
size_t wt901ble_node::readN(uint8_t *buf, size_t len){
|
||||
size_t offset = 0;
|
||||
offset = serial_->read(buf,len);
|
||||
return offset;
|
||||
}
|
||||
|
||||
bool wt901ble_node::recvData(uint8_t *buf){
|
||||
bool ret = false;
|
||||
uint8_t ch[2];
|
||||
if(readN(ch, 2) == 2)
|
||||
{
|
||||
if(ch[0]==wt901ble_header_imu[0]&&
|
||||
ch[1]==wt901ble_header_imu[1])
|
||||
{
|
||||
buf[0] = ch[0];
|
||||
buf[1] = ch[1];
|
||||
if(readN(&buf[2],18)==18)
|
||||
{
|
||||
ret = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
// if (readN(buf, wt901ble_data_length) != 20) {
|
||||
// // continue;
|
||||
// return false;
|
||||
// }
|
||||
// if (buf[0] == wt901ble_header_imu[0]&&
|
||||
// buf[1] == wt901ble_header_imu[1])
|
||||
// {
|
||||
// ret = true;
|
||||
// }
|
||||
return ret;
|
||||
}
|
||||
|
||||
bool wt901ble_node::receiveData()
|
||||
{
|
||||
bool ret = false;
|
||||
isDataAvailable = false;
|
||||
uint8_t ch;
|
||||
while (!ret) {
|
||||
|
||||
if(readN(&ch, 1) != 1){
|
||||
continue;
|
||||
}
|
||||
if(ch == wt901ble_header_imu[0]){
|
||||
data_buf[0] = ch;
|
||||
if(readN(&ch, 1) == 1){
|
||||
if(ch == wt901ble_header_imu[2])
|
||||
{
|
||||
data_buf[1] = ch;
|
||||
if(readN(&data_buf[2], 18) == 18)
|
||||
{
|
||||
ret = true;
|
||||
isDataAvailable = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
bool wt901ble_node::detect_port(string& port_name)
|
||||
{
|
||||
bool result = false;
|
||||
// vector<serial::PortInfo> devices_found = serial::list_ports();
|
||||
|
||||
// vector<serial::PortInfo>::iterator iter = devices_found.begin();
|
||||
// bool result = false;
|
||||
// while( iter != devices_found.end() )
|
||||
// {
|
||||
// serial::PortInfo device = *iter++;
|
||||
// // ROS_INFO( "(%s, %s, %s)\n", device.port.c_str(), device.description.c_str(),
|
||||
// // device.hardware_id.c_str() );
|
||||
// if(device.port == port_name)
|
||||
// {
|
||||
// // ROS_INFO("Found port: %s",device.port.c_str());
|
||||
// result = true;
|
||||
// break;
|
||||
// }
|
||||
// }
|
||||
// return result;
|
||||
string product = "USB Serial";
|
||||
char _port[50] = "";
|
||||
udevadmInfo *ludev = new udevadmInfo(product.c_str());
|
||||
if(ludev->init() == EXIT_FAILURE)
|
||||
return false;
|
||||
if(!ludev->scanDevices()) { return false; }
|
||||
else {
|
||||
strcpy(_port, ludev->port);
|
||||
}
|
||||
ROS_INFO("Found port: %s",_port);
|
||||
|
||||
if(strstr(_port,"/dev/ttyUSB") != NULL) {
|
||||
// std::string cmd_ = "sudo chmod 777 " + (std::string)_port;
|
||||
// system(cmd_.c_str());
|
||||
userParams->portname = (std::string)_port;
|
||||
result = true;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
}
|
||||
19
Devices/Packages/wit_wt901ble_reader/src/wit_wt901ble_reader_main.cc
Executable file
19
Devices/Packages/wit_wt901ble_reader/src/wit_wt901ble_reader_main.cc
Executable file
@@ -0,0 +1,19 @@
|
||||
#include "wit_wt901ble_reader/wit_wt901ble_reader.h"
|
||||
|
||||
using namespace std;
|
||||
using namespace wt901ble_reader;
|
||||
|
||||
wt901ble_node* node;
|
||||
Diagnostics* diagnostics_node;
|
||||
int main(int argc, char** argv)
|
||||
{
|
||||
ros::init(argc, argv, "wit_wt901ble_reader_node");
|
||||
ros::start();
|
||||
string nodename = ros::this_node::getName();
|
||||
node = new wt901ble_node(nodename);
|
||||
diagnostics_node = new Diagnostics(nodename);
|
||||
ros::spin();
|
||||
delete(node);
|
||||
delete(diagnostics_node);
|
||||
return 0;
|
||||
}
|
||||
Reference in New Issue
Block a user