Merge branch 'main' of ssh://gitea.qutcmrt.top:222/hara/mid360 into main
This commit is contained in:
commit
b67fa57651
@ -147,7 +147,7 @@ void write3float2(float x,float y,float yaw)
|
|||||||
unsigned char buf[16] = {0};//
|
unsigned char buf[16] = {0};//
|
||||||
buf[0]=0xFF;
|
buf[0]=0xFF;
|
||||||
buf[1]=0x09;
|
buf[1]=0x09;
|
||||||
buf[2]=0x00;
|
buf[2]=0x01;
|
||||||
buf[15]=0xFE;
|
buf[15]=0xFE;
|
||||||
for(int i=0;i<4;i++){
|
for(int i=0;i<4;i++){
|
||||||
buf[i+3]=X.data[i];
|
buf[i+3]=X.data[i];
|
||||||
|
|||||||
@ -8,7 +8,7 @@
|
|||||||
#include <nav_msgs/Odometry.h>
|
#include <nav_msgs/Odometry.h>
|
||||||
#include <boost/asio.hpp>
|
#include <boost/asio.hpp>
|
||||||
#include <geometry_msgs/Twist.h>
|
#include <geometry_msgs/Twist.h>
|
||||||
void write3float2(float x,float y,float yaw);
|
extern void write3float2(float x,float y,float yaw);
|
||||||
extern void serialInit();
|
extern void serialInit();
|
||||||
extern void writeSpeed(double Left_v, double Right_v,unsigned char ctrlFlag);
|
extern void writeSpeed(double Left_v, double Right_v,unsigned char ctrlFlag);
|
||||||
extern void write3float(float x, float y, float yaw);
|
extern void write3float(float x, float y, float yaw);
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user