参考链接
Error Code 1&2 gps_cpp.o ? Catkin Build : Ubuntu 20.04 Ros Neotic Mavros install #1938
1. 问题描述
参考PX4-Autopilot官方文档,以源码方式安装mavros时,catkin build报错如下:
Errors << mavlink:make /home/zichen/catkin_ws/logs/mavlink/build.make.006.log
make[2]: *** [CMakeFiles/paparazzi.xml-v2.0.dir/build.make:63: paparazzi-v2.0-cxx-stamp] Error 1
make[1]: *** [CMakeFiles/Makefile2:145: CMakeFiles/paparazzi.xml-v2.0.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
make[2]: *** [CMakeFiles/standard.xml-v2.0.dir/build.make:63: standard-v2.0-cxx-stamp] Error 1
make[1]: *** [CMakeFiles/Makefile2:118: CMakeFiles/standard.xml-v2.0.dir/all] Error 2
make[2]: *** [CMakeFiles/uAvionix.xml-v2.0.dir/build.make:63: uAvionix-v2.0-cxx-stamp] Error 1
make[1]: *** [CMakeFiles/Makefile2:343: CMakeFiles/uAvionix.xml-v2.0.dir/all] Error 2
make[2]: *** [CMakeFiles/autoquad.xml-v2.0.dir/build.make:63: autoquad-v2.0-cxx-stamp] Error 1
make[1]: *** [CMakeFiles/Makefile2:235: CMakeFiles/autoquad.xml-v2.0.dir/all] Error 2
make[2]: *** [CMakeFiles/matrixpilot.xml-v2.0.dir/build.make:63: matrixpilot-v2.0-cxx-stamp] Error 1
make[1]: *** [CMakeFiles/Makefile2:397: CMakeFiles/matrixpilot.xml-v2.0.dir/all] Error 2
make[2]: *** [CMakeFiles/ualberta.xml-v2.0.dir/build.make:63: ualberta-v2.0-cxx-stamp] Error 1
make[1]: *** [CMakeFiles/Makefile2:289: CMakeFiles/ualberta.xml-v2.0.dir/all] Error 2
make[2]: *** [CMakeFiles/ASLUAV.xml-v2.0.dir/build.make:63: ASLUAV-v2.0-cxx-stamp] Error 1
make[1]: *** [CMakeFiles/Makefile2:640: CMakeFiles/ASLUAV.xml-v2.0.dir/all] Error 2
make[2]: *** [CMakeFiles/ardupilotmega.xml-v2.0.dir/build.make:63: ardupilotmega-v2.0-cxx-stamp] Error 1
make[1]: *** [CMakeFiles/Makefile2:262: CMakeFiles/ardupilotmega.xml-v2.0.dir/all] Error 2
make[2]: *** [CMakeFiles/all.xml-v2.0.dir/build.make:63: all-v2.0-cxx-stamp] Error 1
make[1]: *** [CMakeFiles/Makefile2:694: CMakeFiles/all.xml-v2.0.dir/all] Error 2
make: *** [Makefile:118: all] Error 2
cd /home/zichen/catkin_ws/build/mavlink; catkin build --get-env mavlink | catkin env -si /usr/bin/make --jobserver-auth=3,4; cd -
2. 问题分析与解决
参考文首链接可以得知,问题由mavlink引起。具体而言,ROS kinetic版本的mavlink中,GPS2_RAW的消息定义不完整,与ROS noetic版本的mavros产生了不兼容。解决方法如下:
- 打开 ~/catkin_ws/src/mavlink/message_definitions/v1.0/common.xml
- 复制"GPS_RAW_INT"消息的<extensions/>部分;
- 替换掉同文件中"GPS2_RAW"的<extensions/>
需要复制的代码如下:
<extensions/>
<field type="int32_t" name="alt_ellipsoid" units="mm">Altitude (above WGS84, EGM96 ellipsoid). Positive for up.</field>
<field type="uint32_t" name="h_acc" units="mm">Position uncertainty.</field>
<field type="uint32_t" name="v_acc" units="mm">Altitude uncertainty.</field>
<field type="uint32_t" name="vel_acc" units="mm">Speed uncertainty.</field>
<field type="uint32_t" name="hdg_acc" units="degE5">Heading / track uncertainty</field>
<field type="uint16_t" name="yaw" units="cdeg">Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.</field>
完成替换后,"GPS2_RAW"部分应如下所示;
<message id="124" name="GPS2_RAW">
<description>Second GPS data.</description>
<field type="uint64_t" name="time_usec" units="us">Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.</field>
<field type="uint8_t" name="fix_type" enum="GPS_FIX_TYPE">GPS fix type.</field>
<field type="int32_t" name="lat" units="degE7">Latitude (WGS84)</field>
<field type="int32_t" name="lon" units="degE7">Longitude (WGS84)</field>
<field type="int32_t" name="alt" units="mm">Altitude (MSL). Positive for up.</field>
<field type="uint16_t" name="eph">GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX</field>
<field type="uint16_t" name="epv">GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX</field>
<field type="uint16_t" name="vel" units="cm/s">GPS ground speed. If unknown, set to: UINT16_MAX</field>
<field type="uint16_t" name="cog" units="cdeg">Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX</field>
<field type="uint8_t" name="satellites_visible">Number of satellites visible. If unknown, set to 255</field>
<field type="uint8_t" name="dgps_numch">Number of DGPS satellites</field>
<field type="uint32_t" name="dgps_age" units="ms">Age of DGPS info</field>
<extensions/>
<field type="int32_t" name="alt_ellipsoid" units="mm">Altitude (above WGS84, EGM96 ellipsoid). Positive for up.</field>
<field type="uint32_t" name="h_acc" units="mm">Position uncertainty.</field>
<field type="uint32_t" name="v_acc" units="mm">Altitude uncertainty.</field>
<field type="uint32_t" name="vel_acc" units="mm">Speed uncertainty.</field>
<field type="uint32_t" name="hdg_acc" units="degE5">Heading / track uncertainty</field>
<field type="uint16_t" name="yaw" units="cdeg">Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.</field>
</message>