利用ROS打印novatel_msgs/INSPVAX
零、写在前面
最近在尝试跑UrbanNav数据集,该数据集是利用GNSS和RTK技术提供车辆运动轨迹和姿态旋转的真值,利用ros跑数据集后,真值通过/novatel_data/inspvax话题提供,利用:
rostopic info /novatel_data/inspvax
查看话题类型为novatel_msgs/INSPVAX,无法直接通过echo打印消息,报错如下:
rostopic echo /novatel_data/inspvax
ERROR: Cannot load message class for [novatel_msgs/INSPVAX]. Are your messages built?
一、C++&ROS订阅
最开始的想法是利用ROS写个cpp文件,直接打印数据,那么需要创建工作空间,我的过程如下:
mkdir -p test_ws/src
cd test_ws
catkin_make
在创建工作空间后,创建功能包,我的功能包命名为imu_predict_test,依赖项有roscpp、rospy、std_msgs,然后在功能包下创建test_gt.cpp,并修改对应的CmakeList文件如下:
add_executable(test_gt_node src/test_gt.cpp)
target_link_libraries(test_gt_node${catkin_LIBRARIES}
)
想要订阅/novatel_data/inspvax话题,就需要novatel_msgs/INSPVAX类型的指针,也就是需要包含以下头文件
#include <ros/ros.h>
#include <novatel_msgs/INSPVAX.h>
但是报错,显示无法找到#include <novatel_msgs/INSPVAX.h>
二、解决措施
查阅novatel_msgs的wiki novatel_msgs(注意科学上网),根据Source将novatel_span_driver安装到test_ws的工作空间下,即:
git clone https://github.com/ros-drivers/novatel_span_driver.git
随后修改CMakeLists.txt,需要增加
find_package(catkin REQUIRED COMPONENTSroscpprospystd_msgsnovatel_msgs
)
catkin_package(INCLUDE_DIRS includeLIBRARIES imu_predict_testCATKIN_DEPENDS roscpp rospy std_msgsnovatel_msgsDEPENDS EIGEN3
)
以及package.xml文件,修改如下:
<build_depend>novatel_msgs</build_depend>
<build_export_depend>novatel_msgs</build_export_depend>
<exec_depend>novatel_msgs</exec_depend>
随后重新在test_ws空间下先source ./devel/setup.bash,再catkin_make,报错解决,可以订阅/novatel_data/inspvax话题
三、消息内容查看及时间戳输出
目前只是可以通过回调函数订阅该话题,但是该话题具体包含哪些消息是不清楚的,因此,在test_ws下输入如下指令:
roscd novatel_msgs
cat msg/INSPVAX.msg
就会显示出该话题包含的所有消息,如下:
# message 1465
novatel_msgs/CommonHeader header# Table 29 in the SPAN on OEM6 manual:
# See: http://www.novatel.com/assets/Documents/Manuals/OM-20000144UM.pdf#page=121
uint32 ins_status
uint32 INS_STATUS_INACTIVE=0
uint32 INS_STATUS_ALIGNING=1
uint32 INS_STATUS_HIGH_VARIANCE=2
uint32 INS_STATUS_SOLUTION_GOOD=3
uint32 INS_STATUS_SOLUTION_FREE=6
uint32 INS_STATUS_ALIGNMENT_COMPLETE=7
uint32 INS_STATUS_DETERMINING_ORIENTATION=8
uint32 INS_STATUS_WAITING_INITIALPOS=9# Table 30 in the SPAN on OEM6 manual:
# See: http://www.novatel.com/assets/Documents/Manuals/OM-20000144UM.pdf#page=124
uint32 position_type
uint32 POSITION_TYPE_NONE=0
uint32 POSITION_TYPE_SBAS=52
uint32 POSITION_TYPE_PSEUDORANGE_SINGLE_POINT=53
uint32 POSITION_TYPE_PSEUDORANGE_DIFFERENTIAL=54
uint32 POSITION_TYPE_RTK_FLOAT=55
uint32 POSITION_TYPE_RTK_FIXED=56
uint32 POSITION_TYPE_OMNISTAR=57
uint32 POSITION_TYPE_OMNISTAR_HP=58
uint32 POSITION_TYPE_OMNISTAR_XP=59
uint32 POSITION_TYPE_PPP_CONVERGING=73
uint32 POSITION_TYPE_PPP=74float64 latitude
float64 longitude
float64 altitudefloat32 undulationfloat64 north_velocity
float64 east_velocity
float64 up_velocityfloat64 roll
float64 pitch
float64 azimuthfloat32 latitude_std
float32 longitude_std
float32 altitude_stdfloat32 north_velocity_std
float32 east_velocity_std
float32 up_velocity_stdfloat32 roll_std
float32 pitch_std
float32 azimuth_stduint32 extended_status
uint32 EXTENDED_STATUS_POSITION_UPDATE_APPLIED=1
uint32 EXTENDED_STATUS_PHASE_UPDATE_APPLIED=2
uint32 EXTENDED_STATUS_ZUPT_APPLIED=4
uint32 EXTENDED_STATUS_WHEEL_SENSOR_APPLIED=8
uint32 EXTENDED_STATUS_HEADING_UPDATE_APPLIED=16
uint32 EXTENDED_STATUS_INS_SOLUTION_CONVERGED=64uint16 seconds_since_update
可以看到,包含经纬度、欧拉角等信息。
通常情况下,时间信息包含在novatel_msgs/CommonHeader header中,因此我们需要通过如下命令查看里面具体包含哪些时间信息:
cd ~/catkin_ws/src/novatel_msgs/msg/
cat CommonHeader.msg
可以看到header中包含时间相关的信息如下:
因此,需要将gps的时间转换成ROS时间进行输出,代码如下:
#include <ros/ros.h>
#include <novatel_msgs/INSPVAX.h>
#include <ctime>// 时间戳转换
const uint32_t gps_to_unix = 315964800; // GPS时间到Unix时间的固定偏移
const uint32_t leap_seconds = 18; // 截至2023年的闰秒数void inspvaxCallback(const novatel_msgs::INSPVAX::ConstPtr& msg) {// 打印Novatel自定义Header(注意字段名不同!)ROS_INFO("--- INSPVAX Message ---");// 计算Unix时间戳(秒)double unix_sec = msg->header.gps_week * 604800 + msg->header.gps_week_seconds / 1000.0 + gps_to_unix - leap_seconds;// 转换为ROS时间(注意:gps_week_seconds本身可能包含小数秒)ros::Time ros_time_stamp = ros::Time(unix_sec);ROS_INFO(" TIME_STAMP: %d.%09d", ros_time_stamp.sec, ros_time_stamp.nsec);
}int main(int argc, char** argv) {ros::init(argc, argv, "inspvax_listener");ros::NodeHandle nh;ros::Subscriber sub = nh.subscribe("/novatel_data/inspvax", 1000, inspvaxCallback);ros::spin();return 0;
}
输出结果如下:
输出成功!