使用roboware-studio从零开始--实现RTK串口数据获取和解析

1、安装测试(去官网下载即可)

$ cd code/code20230501
$ ls 
roboware-studio_1.1.0-1514335284_amd64.deb
$ sudo apt-get update
$ sudo apt install -f
# $ sudo apt-get install ros-melodic-combined-robot-hw
$ sudo dpkg roboware-studio_1.1.0-1514335284_amd64.deb

安装完成后,在终端直接在终端输入打开软件:

$ roboware-studio

2、RoboWare使用

1、基本工作区创建

文件选项栏下选择新建工作区,这里工作区名字为catkin_ws_rtk_test1

 修改资源管理器为Released并 点击ROS--->构建  相当于执行catkin_init_workspace,生成了CMakeList文件的结果。

 

 2、创建功能包

右键src选择 新建ros包

命名为integratednavigation回车,发现自动生成了CMakeList.txt和package.xml

 3、配置功能包依赖

 输入roscpp std_msgs rospy message_generation 点enter

4、添加节点文件main.cpp

右击integratednavigation功能包,选择 新建src文件夹

右键integratednavigation/src 新建cpp文件 输入main.cpp  按住tab键  弹出的窗口选择加入到新的可执行文件中

 main.cpp

#include <ros/ros.h>
#include <iostream>
#include <unistd.h>
#include <string>
#include <vector>   
#include <sstream> 
#include <fstream>

#include <integratednavigation/integratedNavigationMsg.h>
#include "integratednavigation/uarta.h"

/* buffer of receive */
char recvBuff[1024];

/* data of type of string be converted to type of number */
template <typename Type>
Type stringToNum(const std::string &str)
{
	std::stringstream iss(str);
	Type num;
	iss >> num;
	return num;
}


int main( int argc, char **argv )
{
	std::cout<<"Program begins ... "<<std::endl;
	
	int recvCount = 0;
	
	int previous = 0, rear = 0; // pointer to indicate the position of the exact data int a receive buffer.

	/* init the ros */
	ros::init( argc, argv, "IntegrateNavigationSystem" );
	ros::NodeHandle n;

	/* Publisher of the integrated navigation data */
	ros::Publisher pub = n.advertise<IntegratedNavigation::integratedNavigationMsg>( "/integratedNavigation/data", 1);


	/* open the uart device */
	int uart_fd = open_port();
	std::cout<<"uart fd = "<<uart_fd <<std::endl;
	if( uart_fd > 0 ){
		if( set_opt( uart_fd ) != true ){
			std::cerr<<"set port failed ... "<<std::endl;
			return false;
		}
	}
	else{
		std::cerr<<"open port failed ..."<<std::endl;
		exit(-1);
	}
	sleep( 1 );


	std::string s1; 
	std::vector<std::string> arr1; // define a vector of string
	int position = 0;	
	IntegratedNavigation::integratedNavigationMsg recvMsg;

	while(ros::ok()){
	std::cout<<"ros::ok() = "<<ros::ok() <<std::endl;
		memset( recvBuff, 0, sizeof( recvBuff ) );
		if( recvData( uart_fd, recvBuff, sizeof( recvBuff ) ) ){
			if( recvCount <= 1 ) recvCount ++;
			if( recvCount > 1 ){
				/* parse the one frame of message */
				s1 = recvBuff;
				std::cout<<"s1 = "<< s1 <<std::endl;
				std::cout<<"length = "<<s1.length()<<std::endl;
				do{
					std::string tmp_s;
					position = s1.find(","); //找到逗号的位置     
					tmp_s = s1.substr(0, position); //截取需要的字符串      
					s1.erase(0, position + 1); //将已读取的数据删去       
					arr1.push_back(tmp_s);   //将字符串压入容器中    
				} while (position != -1);
	
				int d0 = stringToNum<int>( arr1[1] ); // GPSWeek 
				//printf("GPSWeek = %d\r\n", d0);
				recvMsg.GPSWeek = d0;
				double d1 = stringToNum<double>( arr1[2] ); // GPSTime 
				//printf( "GPSTime = %f\r\n", d1 );
				recvMsg.GPSTime = d1;
				double d2 = stringToNum<double>( arr1[3] ); // Heading 
				//printf("heading = %f\r\n", d2);
				recvMsg.Heading = d2;
				double d3 = stringToNum<double>( arr1[4] ); // Pitch
				//printf( "pitch = %f\r\n", d3 ); 
				recvMsg.Pitch = d3;
				double d4 = stringToNum<double>( arr1[5] ); // Roll
				//printf( "roll = %f\r\n", d4 ); 
				recvMsg.Roll = d4;
				double d5 = stringToNum<double>( arr1[6] ); // gyroX
        	       	        //printf( "gyroX = %f\r\n", d5 );
				recvMsg.gyroX = d5;
				double d6 = stringToNum<double>( arr1[7] ); // gyroY
        	       	        //printf( "gyroY = %f\r\n", d6 );
				recvMsg.gyroY = d6;
				double d7 = stringToNum<double>( arr1[8] ); // gyroZ
               		        //printf( "gyroZ = %f\r\n", d7 );
				recvMsg.gyroZ = d7;
				double d8 = stringToNum<double>( arr1[9] ); // accX
        	                //printf( "accX = %f\r\n", d8 );
				recvMsg.accX = d8;
				double d9 = stringToNum<double>( arr1[10] ); // accY
                	        //printf( "accY = %f\r\n", d9 );
				recvMsg.accY = d9;
				double d10 = stringToNum<double>( arr1[11] ); // accZ
                	       	//printf( "accZ = %f\r\n", d10 );
				recvMsg.accZ = d10;
				double d11 = stringToNum<double>( arr1[12] ); // latitude
	       	                //printf( "latitude = %f\r\n", d11 );
				recvMsg.Lattitude = d11;
				double d12 = stringToNum<double>( arr1[13] ); // longitude
                	        //printf( "longtitude = %f\r\n", d12 );
				recvMsg.Longitude = d12;
				double d13 = stringToNum<double>( arr1[14] ); // attitude
                	    	//printf( "attitude = %f\r\n", d13 );
				recvMsg.Altitude = d13;
				double d14 = stringToNum<double>( arr1[15] ); // Ve
	       	                //printf( "Ve = %f\r\n", d14 );
				recvMsg.Ve = d14;
				double d15 = stringToNum<double>( arr1[16] ); // Vn
	       	                //printf( "Vn = %f\r\n", d15 );
				recvMsg.Vn = d15;
				double d16 = stringToNum<double>( arr1[17] ); // Vu
       		                //printf( "Vu = %f\r\n", d16 );
				recvMsg.Vu = d16;
				double d17 = stringToNum<double>( arr1[18] ); // V
        	      	        //printf( "V = %f\r\n", d17 );
				recvMsg.Baseline = d17;
				int d18 = stringToNum<int>( arr1[19] ); // NSV1 
                	       // printf( "NSV1 = %d\r\n", d18 );
				recvMsg.NSV1 = d18;
				int d19 = stringToNum<int>( arr1[20] ); // NSV2
	                        //printf( "NSV2 = %d\r\n", d19 );
				recvMsg.NSV2 = d19;
				char d20 = stringToNum<char>( arr1[21] ); // status
        	                //printf( "status = %d\r\n", d20 );
				recvMsg.Status = d20;
				double d21 = stringToNum<double>( arr1[22] ); // age
               		        //printf( "age = %f\r\n", d21 );
				recvMsg.Age = d21;
				for (size_t i = 0; i < 20; i++)
				{
					/* code */
					std::cout << "arr1[]" <<  i  << "::"<< arr1[i] << std::endl;
				}
				
				arr1.clear();
				recvMsg.header.stamp = ros::Time::now();
				pub.publish( recvMsg );
			}
		}
	}

	return 0;
}

5、添加include文件

右击integratednavigation功能包,选择 新建include文件夹

右键integratednavigation/include/integratednavigation 新建.h文件 输入integratedNavigationMsg.h 按住tab键 弹出的窗口选择加入到新的库文件中

 integratedNavigationMsg.h

// Generated by gencpp from file IntegratedNavigation/integratedNavigationMsg.msg
// DO NOT EDIT!


#ifndef INTEGRATEDNAVIGATION_MESSAGE_INTEGRATEDNAVIGATIONMSG_H
#define INTEGRATEDNAVIGATION_MESSAGE_INTEGRATEDNAVIGATIONMSG_H


#include <string>
#include <vector>
#include <memory>

#include <ros/types.h>
#include <ros/serialization.h>
#include <ros/builtin_message_traits.h>
#include <ros/message_operations.h>

#include <std_msgs/Header.h>

namespace IntegratedNavigation
{
template <class ContainerAllocator>
struct integratedNavigationMsg_
{
  typedef integratedNavigationMsg_<ContainerAllocator> Type;

  integratedNavigationMsg_()
    : header()
    , GPSWeek(0)
    , GPSTime(0.0)
    , Heading(0.0)
    , Pitch(0.0)
    , Roll(0.0)
    , gyroX(0.0)
    , gyroY(0.0)
    , gyroZ(0.0)
    , accX(0.0)
    , accY(0.0)
    , accZ(0.0)
    , Lattitude(0.0)
    , Longitude(0.0)
    , Altitude(0.0)
    , Ve(0.0)
    , Vn(0.0)
    , Vu(0.0)
    , Baseline(0.0)
    , NSV1(0)
    , NSV2(0)
    , Status(0)
    , Age(0.0)
    , warning(0)  {
    }
  integratedNavigationMsg_(const ContainerAllocator& _alloc)
    : header(_alloc)
    , GPSWeek(0)
    , GPSTime(0.0)
    , Heading(0.0)
    , Pitch(0.0)
    , Roll(0.0)
    , gyroX(0.0)
    , gyroY(0.0)
    , gyroZ(0.0)
    , accX(0.0)
    , accY(0.0)
    , accZ(0.0)
    , Lattitude(0.0)
    , Longitude(0.0)
    , Altitude(0.0)
    , Ve(0.0)
    , Vn(0.0)
    , Vu(0.0)
    , Baseline(0.0)
    , NSV1(0)
    , NSV2(0)
    , Status(0)
    , Age(0.0)
    , warning(0)  {
  (void)_alloc;
    }



   typedef  ::std_msgs::Header_<ContainerAllocator>  _header_type;
  _header_type header;

   typedef int32_t _GPSWeek_type;
  _GPSWeek_type GPSWeek;

   typedef double _GPSTime_type;
  _GPSTime_type GPSTime;

   typedef double _Heading_type;
  _Heading_type Heading;

   typedef double _Pitch_type;
  _Pitch_type Pitch;

   typedef double _Roll_type;
  _Roll_type Roll;

   typedef double _gyroX_type;
  _gyroX_type gyroX;

   typedef double _gyroY_type;
  _gyroY_type gyroY;

   typedef double _gyroZ_type;
  _gyroZ_type gyroZ;

   typedef double _accX_type;
  _accX_type accX;

   typedef double _accY_type;
  _accY_type accY;

   typedef double _accZ_type;
  _accZ_type accZ;

   typedef double _Lattitude_type;
  _Lattitude_type Lattitude;

   typedef double _Longitude_type;
  _Longitude_type Longitude;

   typedef double _Altitude_type;
  _Altitude_type Altitude;

   typedef double _Ve_type;
  _Ve_type Ve;

   typedef double _Vn_type;
  _Vn_type Vn;

   typedef double _Vu_type;
  _Vu_type Vu;

   typedef double _Baseline_type;
  _Baseline_type Baseline;

   typedef int32_t _NSV1_type;
  _NSV1_type NSV1;

   typedef int32_t _NSV2_type;
  _NSV2_type NSV2;

   typedef int8_t _Status_type;
  _Status_type Status;

   typedef float _Age_type;
  _Age_type Age;

   typedef int8_t _warning_type;
  _warning_type warning;





  typedef boost::shared_ptr< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> > Ptr;
  typedef boost::shared_ptr< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> const> ConstPtr;

}; // struct integratedNavigationMsg_

typedef ::IntegratedNavigation::integratedNavigationMsg_<std::allocator<void> > integratedNavigationMsg;

typedef boost::shared_ptr< ::IntegratedNavigation::integratedNavigationMsg > integratedNavigationMsgPtr;
typedef boost::shared_ptr< ::IntegratedNavigation::integratedNavigationMsg const> integratedNavigationMsgConstPtr;

// constants requiring out of line definition



template<typename ContainerAllocator>
std::ostream& operator<<(std::ostream& s, const ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> & v)
{
ros::message_operations::Printer< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> >::stream(s, "", v);
return s;
}


template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator1> & lhs, const ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator2> & rhs)
{
  return lhs.header == rhs.header &&
    lhs.GPSWeek == rhs.GPSWeek &&
    lhs.GPSTime == rhs.GPSTime &&
    lhs.Heading == rhs.Heading &&
    lhs.Pitch == rhs.Pitch &&
    lhs.Roll == rhs.Roll &&
    lhs.gyroX == rhs.gyroX &&
    lhs.gyroY == rhs.gyroY &&
    lhs.gyroZ == rhs.gyroZ &&
    lhs.accX == rhs.accX &&
    lhs.accY == rhs.accY &&
    lhs.accZ == rhs.accZ &&
    lhs.Lattitude == rhs.Lattitude &&
    lhs.Longitude == rhs.Longitude &&
    lhs.Altitude == rhs.Altitude &&
    lhs.Ve == rhs.Ve &&
    lhs.Vn == rhs.Vn &&
    lhs.Vu == rhs.Vu &&
    lhs.Baseline == rhs.Baseline &&
    lhs.NSV1 == rhs.NSV1 &&
    lhs.NSV2 == rhs.NSV2 &&
    lhs.Status == rhs.Status &&
    lhs.Age == rhs.Age &&
    lhs.warning == rhs.warning;
}

template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator1> & lhs, const ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator2> & rhs)
{
  return !(lhs == rhs);
}


} // namespace IntegratedNavigation

namespace ros
{
namespace message_traits
{





template <class ContainerAllocator>
struct IsFixedSize< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> >
  : FalseType
  { };

template <class ContainerAllocator>
struct IsFixedSize< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> const>
  : FalseType
  { };

template <class ContainerAllocator>
struct IsMessage< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> >
  : TrueType
  { };

template <class ContainerAllocator>
struct IsMessage< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> const>
  : TrueType
  { };

template <class ContainerAllocator>
struct HasHeader< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> >
  : TrueType
  { };

template <class ContainerAllocator>
struct HasHeader< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> const>
  : TrueType
  { };


template<class ContainerAllocator>
struct MD5Sum< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> >
{
  static const char* value()
  {
    return "041e1fa850daadf3d28954c7ff76c76d";
  }

  static const char* value(const ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator>&) { return value(); }
  static const uint64_t static_value1 = 0x041e1fa850daadf3ULL;
  static const uint64_t static_value2 = 0xd28954c7ff76c76dULL;
};

template<class ContainerAllocator>
struct DataType< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> >
{
  static const char* value()
  {
    return "IntegratedNavigation/integratedNavigationMsg";
  }

  static const char* value(const ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator>&) { return value(); }
};

template<class ContainerAllocator>
struct Definition< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> >
{
  static const char* value()
  {
    return "std_msgs/Header header\n"
"int32 GPSWeek\n"
"float64 GPSTime\n"
"float64 Heading\n"
"float64 Pitch\n"
"float64 Roll\n"
"float64 gyroX\n"
"float64 gyroY\n"
"float64 gyroZ\n"
"float64 accX\n"
"float64 accY\n"
"float64 accZ\n"
"float64 Lattitude\n"
"float64 Longitude\n"
"float64 Altitude\n"
"float64 Ve # velocity towards east\n"
"float64 Vn # velocity towards north\n"
"float64 Vu\n"
"float64 Baseline # Velocity of vehicle\n"
"int32 NSV1 # number of the settlelites\n"
"int32 NSV2\n"
"int8 Status\n"
"float32 Age\n"
"int8 warning\n"
"\n"
"\n"
"\n"
"\n"
"\n"
"================================================================================\n"
"MSG: std_msgs/Header\n"
"# Standard metadata for higher-level stamped data types.\n"
"# This is generally used to communicate timestamped data \n"
"# in a particular coordinate frame.\n"
"# \n"
"# sequence ID: consecutively increasing ID \n"
"uint32 seq\n"
"#Two-integer timestamp that is expressed as:\n"
"# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n"
"# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n"
"# time-handling sugar is provided by the client library\n"
"time stamp\n"
"#Frame this data is associated with\n"
"string frame_id\n"
;
  }

  static const char* value(const ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator>&) { return value(); }
};

} // namespace message_traits
} // namespace ros

namespace ros
{
namespace serialization
{

  template<class ContainerAllocator> struct Serializer< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> >
  {
    template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
    {
      stream.next(m.header);
      stream.next(m.GPSWeek);
      stream.next(m.GPSTime);
      stream.next(m.Heading);
      stream.next(m.Pitch);
      stream.next(m.Roll);
      stream.next(m.gyroX);
      stream.next(m.gyroY);
      stream.next(m.gyroZ);
      stream.next(m.accX);
      stream.next(m.accY);
      stream.next(m.accZ);
      stream.next(m.Lattitude);
      stream.next(m.Longitude);
      stream.next(m.Altitude);
      stream.next(m.Ve);
      stream.next(m.Vn);
      stream.next(m.Vu);
      stream.next(m.Baseline);
      stream.next(m.NSV1);
      stream.next(m.NSV2);
      stream.next(m.Status);
      stream.next(m.Age);
      stream.next(m.warning);
    }

    ROS_DECLARE_ALLINONE_SERIALIZER
  }; // struct integratedNavigationMsg_

} // namespace serialization
} // namespace ros

namespace ros
{
namespace message_operations
{

template<class ContainerAllocator>
struct Printer< ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator> >
{
  template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::IntegratedNavigation::integratedNavigationMsg_<ContainerAllocator>& v)
  {
    s << indent << "header: ";
    s << std::endl;
    Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + "  ", v.header);
    s << indent << "GPSWeek: ";
    Printer<int32_t>::stream(s, indent + "  ", v.GPSWeek);
    s << indent << "GPSTime: ";
    Printer<double>::stream(s, indent + "  ", v.GPSTime);
    s << indent << "Heading: ";
    Printer<double>::stream(s, indent + "  ", v.Heading);
    s << indent << "Pitch: ";
    Printer<double>::stream(s, indent + "  ", v.Pitch);
    s << indent << "Roll: ";
    Printer<double>::stream(s, indent + "  ", v.Roll);
    s << indent << "gyroX: ";
    Printer<double>::stream(s, indent + "  ", v.gyroX);
    s << indent << "gyroY: ";
    Printer<double>::stream(s, indent + "  ", v.gyroY);
    s << indent << "gyroZ: ";
    Printer<double>::stream(s, indent + "  ", v.gyroZ);
    s << indent << "accX: ";
    Printer<double>::stream(s, indent + "  ", v.accX);
    s << indent << "accY: ";
    Printer<double>::stream(s, indent + "  ", v.accY);
    s << indent << "accZ: ";
    Printer<double>::stream(s, indent + "  ", v.accZ);
    s << indent << "Lattitude: ";
    Printer<double>::stream(s, indent + "  ", v.Lattitude);
    s << indent << "Longitude: ";
    Printer<double>::stream(s, indent + "  ", v.Longitude);
    s << indent << "Altitude: ";
    Printer<double>::stream(s, indent + "  ", v.Altitude);
    s << indent << "Ve: ";
    Printer<double>::stream(s, indent + "  ", v.Ve);
    s << indent << "Vn: ";
    Printer<double>::stream(s, indent + "  ", v.Vn);
    s << indent << "Vu: ";
    Printer<double>::stream(s, indent + "  ", v.Vu);
    s << indent << "Baseline: ";
    Printer<double>::stream(s, indent + "  ", v.Baseline);
    s << indent << "NSV1: ";
    Printer<int32_t>::stream(s, indent + "  ", v.NSV1);
    s << indent << "NSV2: ";
    Printer<int32_t>::stream(s, indent + "  ", v.NSV2);
    s << indent << "Status: ";
    Printer<int8_t>::stream(s, indent + "  ", v.Status);
    s << indent << "Age: ";
    Printer<float>::stream(s, indent + "  ", v.Age);
    s << indent << "warning: ";
    Printer<int8_t>::stream(s, indent + "  ", v.warning);
  }
};

} // namespace message_operations
} // namespace ros

#endif // INTEGRATEDNAVIGATION_MESSAGE_INTEGRATEDNAVIGATIONMSG_H

同样操作新建头文件 uarta.h

#ifndef __UARTA_H_
#define __UARTA_H_

#include <iostream>
#include <stdlib.h>
#include <unistd.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <errno.h>
#include <termios.h>
#include <string.h>

int open_port();
int set_opt( int fd );
bool recvData( int fd, char *recvbuff, int n );
bool send_Byte( int fd, char byte );

int open_port()
{
    char *dev = "/dev/ttyUSB0";
    int fd = open( dev, O_RDWR | O_NOCTTY | O_NDELAY );
    if( fd == -1 ){
        std::cout<<"error1 ..."<<std::endl;
        return false;
    }
    if( fcntl( fd, F_SETFL, 0 ) < 0 ){
        std::cout<<"error2 ..."<<std::endl;
        return false;
    }
    if( isatty( STDIN_FILENO ) == 0 ){
        std::cout<<"error3 ..."<<std::endl;
        return false;
    }
    std::cout<<"open port successfully ..."<<std::endl;
    return fd;
}

int set_opt( int fd )
{
    struct termios newtio, oldtio;
    if( tcgetattr( fd, &oldtio ) != 0 ){
        std::cout<<"read old serial attributions failed ..."<<std::endl;
        return false;
    }
    bzero( &newtio, sizeof( newtio ) );

    newtio.c_cflag |= CLOCAL | CREAD;

    newtio.c_cflag &= ~CSIZE;
    newtio.c_cflag |= CS8;

    newtio.c_cflag &= ~PARENB;

    cfsetispeed( &newtio, B115200 );
    cfsetospeed( &newtio, B115200 );
    
    newtio.c_cflag &= ~CSTOPB;

    newtio.c_cc[VTIME] = 0;
    newtio.c_cc[VMIN] = 1;

    tcflush( fd, TCIFLUSH );
    
    if( ( tcsetattr( fd, TCSANOW, &newtio ) ) != 0 ){
        std::cout<<"com set error ... "<<std::endl;
        return false;
    }
    std::cout<<"set port successfully ..."<<std::endl;
    return true;
}

bool recvData( int fd, char *recvBuff, int n )
{
        int count = 1;
        read( fd, &recvBuff[0], 1 );
        if( recvBuff[0] == '$' ){
                do{
                        read( fd, &recvBuff[ count ], 1 );
                        count ++ ;
		}while( recvBuff[count - 1] != 0x0D && recvBuff[count] != 0x0A );// "count < n " should not be exist in here, maybe, waiting for a test

                std::cout<<"count is: "<<count<<std::endl;
		//for( int i = 1; i < count; i ++ )
		//	std::cout<<"recvBuff["<<i<<"] = "<<recvBuff[i]<<std::endl;
                count = 1;
        }
	else{
		return false;
	}
	return true;
}


bool send_Byte( int fd, char byte )
{
	if( write( fd, &byte, 1 ) != 1){
		return false;
	}
	else{
		return true;
		std::cout<<"send commander successfully ..."<<std::endl;
	}
}

#endif

同4、5添加src文件夹和include文件夹,创建msg文件夹

并新建msg文件integratednavigation.msg

integratednavigation.msg

std_msgs/Header header
int32 GPSWeek
float64 GPSTime
float64 Heading
float64 Pitch
float64 Roll
float64 gyroX
float64 gyroY
float64 gyroZ
float64 accX
float64 accY
float64 accZ
float64 Lattitude
float64 Longitude
float64 Altitude
float64 Ve # velocity towards east
float64 Vn # velocity towards north
float64 Vu
float64 Baseline # Velocity of vehicle
int32 NSV1 # number of the settlelites
int32 NSV2
int8 Status
float32 Age
int8 warning

6、编译执行

快捷键 ctrl + `调起终端,在工作空间下编译:

$ catkin_make
$ souce devel/setup.bash
$ catkin_make
#一开始编译有报错 把功能包下面除src之外的文件删除  重新点击ros-构建 之后编译正常

 新建终端  运行roscore

 可以看到ROS节点已经出现在这里  并执行rosrun

$ rosrun integratednavigation main

 

  • 0
    点赞
  • 2
    收藏
    觉得还不错? 一键收藏
  • 1
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值