|
@@ -5,6 +5,7 @@
|
|
* History:
|
|
* History:
|
|
* 20200401:init this file.
|
|
* 20200401:init this file.
|
|
*************************************************************************/
|
|
*************************************************************************/
|
|
|
|
+#include<ros/ros.h>
|
|
#include<stdio.h>
|
|
#include<stdio.h>
|
|
#include<stdlib.h>
|
|
#include<stdlib.h>
|
|
#include<fcntl.h>
|
|
#include<fcntl.h>
|
|
@@ -14,39 +15,33 @@
|
|
#include<string.h>
|
|
#include<string.h>
|
|
#include<sys/time.h>
|
|
#include<sys/time.h>
|
|
#include<sys/types.h>
|
|
#include<sys/types.h>
|
|
-#include<errno.h>
|
|
|
|
|
|
|
|
-
|
|
|
|
-#define BAUD 9600 //9600 default baund for JY61P
|
|
|
|
|
|
+char r_buf[512];
|
|
|
|
+int port_fd = 0;
|
|
|
|
+float acce[3],angular[3],angle[3],quater[4];
|
|
|
|
|
|
/**********************************************
|
|
/**********************************************
|
|
- * Description:打开串口,输入设备号参数即可.
|
|
|
|
|
|
+ * Description:打开串口,输入各参数即可.
|
|
*********************************************/
|
|
*********************************************/
|
|
-int open_serialPort(const char *path)
|
|
|
|
|
|
+int openSerialPort(const char *path, int baud, int dataBits,
|
|
|
|
+ const char* parity, int stopBit)
|
|
{
|
|
{
|
|
- int fd = open(path, O_RDWR|O_NOCTTY);
|
|
|
|
|
|
+ int fd = 0;
|
|
|
|
+ struct termios terminfo;
|
|
|
|
+ bzero(&terminfo, sizeof(terminfo));
|
|
|
|
+
|
|
|
|
+ fd = open(path, O_RDWR|O_NOCTTY);
|
|
if (-1 == fd)
|
|
if (-1 == fd)
|
|
{
|
|
{
|
|
- return(-1);
|
|
|
|
|
|
+ ROS_ERROR("Open imu dev error:%s", path);
|
|
|
|
+ return -1;
|
|
}
|
|
}
|
|
|
|
|
|
if(isatty(STDIN_FILENO) == 0)
|
|
if(isatty(STDIN_FILENO) == 0)
|
|
{
|
|
{
|
|
- return(-2);
|
|
|
|
|
|
+ ROS_ERROR("IMU dev isatty error !");
|
|
|
|
+ return -2;
|
|
}
|
|
}
|
|
- else
|
|
|
|
- {
|
|
|
|
- return fd;
|
|
|
|
- }
|
|
|
|
-}
|
|
|
|
-
|
|
|
|
-/************************************************************************
|
|
|
|
- * Description:配置可以与串口进行正常数据通信的参数.
|
|
|
|
- ***********************************************************************/
|
|
|
|
-int set_serialPort(int fd, int baud, int dataBits, char parity, int stopBits)
|
|
|
|
-{
|
|
|
|
- struct termios terminfo;
|
|
|
|
- bzero(&terminfo, sizeof(terminfo));
|
|
|
|
|
|
|
|
/*设置串口通信波特率-bps*/
|
|
/*设置串口通信波特率-bps*/
|
|
switch(baud)
|
|
switch(baud)
|
|
@@ -96,12 +91,12 @@ int set_serialPort(int fd, int baud, int dataBits, char parity, int stopBits)
|
|
break;
|
|
break;
|
|
|
|
|
|
default:
|
|
default:
|
|
- printf("Set dataBits error !\n");
|
|
|
|
- return -1;
|
|
|
|
|
|
+ ROS_ERROR("set dataBit error !");
|
|
|
|
+ return -3;
|
|
}
|
|
}
|
|
|
|
|
|
//设置奇偶校验位
|
|
//设置奇偶校验位
|
|
- switch(parity)
|
|
|
|
|
|
+ switch(*parity)
|
|
{
|
|
{
|
|
case 'o': //设置奇校验
|
|
case 'o': //设置奇校验
|
|
case 'O':
|
|
case 'O':
|
|
@@ -123,12 +118,12 @@ int set_serialPort(int fd, int baud, int dataBits, char parity, int stopBits)
|
|
break;
|
|
break;
|
|
|
|
|
|
default:
|
|
default:
|
|
- printf("set parity error !\n");
|
|
|
|
- return -2;
|
|
|
|
|
|
+ ROS_ERROR("set parity error !");
|
|
|
|
+ return -4;
|
|
}
|
|
}
|
|
|
|
|
|
//设置停止位
|
|
//设置停止位
|
|
- switch(stopBits)
|
|
|
|
|
|
+ switch(stopBit)
|
|
{
|
|
{
|
|
case 1:
|
|
case 1:
|
|
terminfo.c_cflag &= ~CSTOPB;
|
|
terminfo.c_cflag &= ~CSTOPB;
|
|
@@ -139,8 +134,8 @@ int set_serialPort(int fd, int baud, int dataBits, char parity, int stopBits)
|
|
break;
|
|
break;
|
|
|
|
|
|
default:
|
|
default:
|
|
- printf("set stopBits error !\n");
|
|
|
|
- return -3;
|
|
|
|
|
|
+ ROS_ERROR("set stopBit error !");
|
|
|
|
+ return -5;
|
|
}
|
|
}
|
|
|
|
|
|
terminfo.c_cc[VTIME] = 10;
|
|
terminfo.c_cc[VTIME] = 10;
|
|
@@ -149,19 +144,19 @@ int set_serialPort(int fd, int baud, int dataBits, char parity, int stopBits)
|
|
|
|
|
|
if((tcsetattr(fd, TCSANOW, &terminfo)) != 0)
|
|
if((tcsetattr(fd, TCSANOW, &terminfo)) != 0)
|
|
{
|
|
{
|
|
- printf("config serialPort params error !\n");
|
|
|
|
- return -4;
|
|
|
|
|
|
+ ROS_ERROR("set imu serial port attr error !");
|
|
|
|
+ return -6;
|
|
}
|
|
}
|
|
|
|
|
|
- return 0;
|
|
|
|
|
|
+ return fd;
|
|
}
|
|
}
|
|
|
|
|
|
/**************************************
|
|
/**************************************
|
|
* Description:关闭串口文件描述符.
|
|
* Description:关闭串口文件描述符.
|
|
*************************************/
|
|
*************************************/
|
|
-int close_serialPort(int fd)
|
|
|
|
|
|
+int closeSerialPort()
|
|
{
|
|
{
|
|
- int ret = close(fd);
|
|
|
|
|
|
+ int ret = close(port_fd);
|
|
return ret;
|
|
return ret;
|
|
}
|
|
}
|
|
|
|
|
|
@@ -184,15 +179,15 @@ int recv_data(int fd, char* recv_buffer, int len)
|
|
return length;
|
|
return length;
|
|
}
|
|
}
|
|
|
|
|
|
-float a[3], w[3], Angle[3], q[4];
|
|
|
|
|
|
+
|
|
/************************************************************
|
|
/************************************************************
|
|
* Description:根据串口数据协议来解析有效数据,
|
|
* Description:根据串口数据协议来解析有效数据,
|
|
***********************************************************/
|
|
***********************************************************/
|
|
void parse_serialData(char chr)
|
|
void parse_serialData(char chr)
|
|
{
|
|
{
|
|
- static char chrBuf[100];
|
|
|
|
|
|
+ static unsigned char chrBuf[100];
|
|
static unsigned char chrCnt = 0;
|
|
static unsigned char chrCnt = 0;
|
|
- signed short sData[4]; //存储8字节的有效信息
|
|
|
|
|
|
+ signed short sData[4]; //save 8 Byte valid info
|
|
unsigned char i = 0;
|
|
unsigned char i = 0;
|
|
char frameSum = 0;
|
|
char frameSum = 0;
|
|
|
|
|
|
@@ -217,88 +212,118 @@ void parse_serialData(char chr)
|
|
return;
|
|
return;
|
|
}
|
|
}
|
|
|
|
|
|
|
|
+ //for(i=0;i<11; i++)
|
|
|
|
+ // printf("0x%x ",chrBuf[i]);
|
|
|
|
+ //printf("\n");
|
|
|
|
+
|
|
memcpy(&sData[0], &chrBuf[2], 8);
|
|
memcpy(&sData[0], &chrBuf[2], 8);
|
|
switch(chrBuf[1])
|
|
switch(chrBuf[1])
|
|
{
|
|
{
|
|
case 0x51: //加速度输出
|
|
case 0x51: //加速度输出
|
|
- for(i=0; i<3; i++)
|
|
|
|
- {
|
|
|
|
- a[i] = (float)sData[i]/32768.0*16.0;
|
|
|
|
- }
|
|
|
|
- printf("a:%6.4f %6.4f %6.4f ", a[0], a[1], a[2]);
|
|
|
|
|
|
+ //ROS_INFO("AccX:%d %d",chrBuf[2], chrBuf[3]);
|
|
|
|
+ //ROS_INFO("AccY:%d %d",chrBuf[4], chrBuf[5]);
|
|
|
|
+ acce[0] = (short)(((short)chrBuf[3]<<8)|chrBuf[2])/32768.0*16.0;
|
|
|
|
+ acce[1] = (short)(((short)chrBuf[5]<<8)|chrBuf[4])/32768.0*16.0;
|
|
|
|
+ acce[2] = (short)(((short)chrBuf[7]<<8)|chrBuf[6])/32768.0*16.0;
|
|
break;
|
|
break;
|
|
|
|
|
|
case 0x52: //角速度输出
|
|
case 0x52: //角速度输出
|
|
- for(i=0; i<3; i++)
|
|
|
|
- {
|
|
|
|
- w[i] = (float)sData[i]/32768.0*2000.0;
|
|
|
|
- }
|
|
|
|
- printf("w:%7.4f %7.4f %7.4f ", w[0], w[1], w[2]);
|
|
|
|
|
|
+ angular[0] = (short)(((short)chrBuf[3]<<8)|chrBuf[2])/32768.0*2000.0;
|
|
|
|
+ angular[1] = (short)(((short)chrBuf[5]<<8)|chrBuf[4])/32768.0*2000.0;
|
|
|
|
+ angular[2] = (short)(((short)chrBuf[7]<<8)|chrBuf[6])/32768.0*2000.0;
|
|
break;
|
|
break;
|
|
|
|
|
|
case 0x53: //角度输出, roll, pitch, yaw
|
|
case 0x53: //角度输出, roll, pitch, yaw
|
|
- for (i=0; i<3; i++)
|
|
|
|
- {
|
|
|
|
- Angle[i] = (float)sData[i]/32768.0*180.0;
|
|
|
|
- }
|
|
|
|
- printf("A:%7.4f %7.4f %7.4f ", Angle[0], Angle[1], Angle[2]);
|
|
|
|
|
|
+ angle[0] = (short)(((short)chrBuf[3]<<8)|chrBuf[2])/32768.0*180.0;
|
|
|
|
+ angle[1] = (short)(((short)chrBuf[5]<<8)|chrBuf[4])/32768.0*180.0;
|
|
|
|
+ angle[2] = (short)(((short)chrBuf[7]<<8)|chrBuf[6])/32768.0*180.0;
|
|
break;
|
|
break;
|
|
|
|
|
|
case 0x59: //四元素输出
|
|
case 0x59: //四元素输出
|
|
- for (i=0; i<4; i++)
|
|
|
|
- {
|
|
|
|
- q[i] = (float)sData[i]/32768.0;
|
|
|
|
- }
|
|
|
|
- printf("q:%6.4f %6.4f %6.4f %6.4f\n", q[0], q[1], q[2], q[3]);
|
|
|
|
|
|
+ quater[0] = (((short)chrBuf[3]<<8)|chrBuf[2])/32768.0;
|
|
|
|
+ quater[1] = (((short)chrBuf[5]<<8)|chrBuf[4])/32768.0;
|
|
|
|
+ quater[2] = (((short)chrBuf[7]<<8)|chrBuf[6])/32768.0;
|
|
|
|
+ quater[3] = (((short)chrBuf[9]<<8)|chrBuf[8])/32768.0;
|
|
break;
|
|
break;
|
|
}
|
|
}
|
|
chrCnt = 0;
|
|
chrCnt = 0;
|
|
}
|
|
}
|
|
|
|
|
|
-int main(void)
|
|
|
|
|
|
+/*****************************************************************
|
|
|
|
+ * Description:根据串口配置信息来配置打开串口,准备进行数据通信
|
|
|
|
+ ****************************************************************/
|
|
|
|
+int initSerialPort(const char* path, const int baud, const int dataBits,
|
|
|
|
+ const char* parity, const int stopBit)
|
|
{
|
|
{
|
|
- int ret = 0;
|
|
|
|
- int port_fd = 0;
|
|
|
|
- char r_buf[512];
|
|
|
|
bzero(r_buf, 512);
|
|
bzero(r_buf, 512);
|
|
- std::string imu_dev;
|
|
|
|
-
|
|
|
|
- port_fd = open_serialPort("/dev/ttyUSB0");
|
|
|
|
|
|
+ port_fd = openSerialPort(path, baud, dataBits, parity, stopBit);
|
|
if(port_fd < 0)
|
|
if(port_fd < 0)
|
|
{
|
|
{
|
|
- printf("open_serialPort error !\n");
|
|
|
|
- exit(EXIT_FAILURE);
|
|
|
|
|
|
+ ROS_ERROR("openSerialPort error !");
|
|
|
|
+ return -1;
|
|
}
|
|
}
|
|
|
|
|
|
- if(set_serialPort(port_fd, BAUD, 8, 'N', 1) < 0)
|
|
|
|
- {
|
|
|
|
- printf("set serialPort failed !\n");
|
|
|
|
- exit(EXIT_FAILURE);
|
|
|
|
- }
|
|
|
|
|
|
+ return 0;
|
|
|
|
+}
|
|
|
|
|
|
- while(1)
|
|
|
|
|
|
+float getAccX()
|
|
|
|
+{
|
|
|
|
+ return acce[0];
|
|
|
|
+}
|
|
|
|
+float getAccY()
|
|
|
|
+{
|
|
|
|
+ return acce[1];
|
|
|
|
+}
|
|
|
|
+float getAccZ()
|
|
|
|
+{
|
|
|
|
+ return acce[2];
|
|
|
|
+}
|
|
|
|
+
|
|
|
|
+float getAngularX()
|
|
|
|
+{
|
|
|
|
+ return angular[0];
|
|
|
|
+}
|
|
|
|
+
|
|
|
|
+float getAngularY()
|
|
|
|
+{
|
|
|
|
+ return angular[1];
|
|
|
|
+}
|
|
|
|
+
|
|
|
|
+float getAngularZ()
|
|
|
|
+{
|
|
|
|
+ return angular[2];
|
|
|
|
+}
|
|
|
|
+
|
|
|
|
+float getAngleX()
|
|
|
|
+{
|
|
|
|
+ return angle[0];
|
|
|
|
+}
|
|
|
|
+float getAngleY()
|
|
|
|
+{
|
|
|
|
+ return angle[1];
|
|
|
|
+}
|
|
|
|
+float getAngleZ()
|
|
|
|
+{
|
|
|
|
+ return angle[2];
|
|
|
|
+}
|
|
|
|
+
|
|
|
|
+int getImuData()
|
|
|
|
+{
|
|
|
|
+ int ret = 0;
|
|
|
|
+ ret = recv_data(port_fd, r_buf, 44);
|
|
|
|
+ if(ret == -1)
|
|
{
|
|
{
|
|
- ret = recv_data(port_fd, r_buf, 44);
|
|
|
|
- if(ret == -1)
|
|
|
|
- {
|
|
|
|
- printf("read serial port data failed !\n");
|
|
|
|
- exit(EXIT_FAILURE);
|
|
|
|
- }
|
|
|
|
-
|
|
|
|
- for (int i=0; i<ret; i++)
|
|
|
|
- {
|
|
|
|
- parse_serialData(r_buf[i]);
|
|
|
|
- }
|
|
|
|
- usleep(1000);
|
|
|
|
|
|
+ ROS_ERROR("read serial port data failed !\n");
|
|
|
|
+ closeSerialPort();
|
|
|
|
+
|
|
|
|
+ return -1;
|
|
}
|
|
}
|
|
|
|
|
|
- ret = close_serialPort(port_fd);
|
|
|
|
- if(ret == -1)
|
|
|
|
|
|
+ for (int i=0; i<ret; i++)
|
|
{
|
|
{
|
|
- printf("close serialPort error !\n");
|
|
|
|
- exit(EXIT_FAILURE);
|
|
|
|
|
|
+ parse_serialData(r_buf[i]);
|
|
}
|
|
}
|
|
|
|
|
|
- exit(EXIT_SUCCESS);
|
|
|
|
|
|
+ return 0;
|
|
}
|
|
}
|
|
|
|
|