测试船体运动正常与否,先设计一个遥控船的运动模型。
1. 通过订阅键盘的遥控信息。
2. 通过串口向stm32向下发送速度信息使船完成遥控运动。
serail包 https://github.com/wjwwood/serial
//xx 20190407
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include "serial/serial.h"
#include<unistd.h> //延时
//xx
#include <xx_msgs/Flag.h>
float linear_vel=0.0,angular_vel=0.0;
union floatData //用于char数组与float之间的转换
{
float f;
unsigned char data[4];
}chaun_linear_vel_send,chuan_angular_vel_send,tuolian_state_send;
// 0x0d "/r" 字符
// 0x0a "/n" 字符
//{0x0,0x02,0x03,0x04,0x05,0x06,0x07,0x08,0x0d,0x0a};
unsigned char send_buf[14]={0x00,0x00,0x00,0x00, //线速度 4个字节
0x00,0x00,0x00,0x00, //角速度
0x00,0x00,0x00,0x00, //拖链标志
0x0d,0x0a}; // "/r/n"
void chuan_vel_callback(const geometry