飞控高度传感器中一般有两种高度:
- 海拔高。也称AMSL(Above Mean Sea Level)height或者geoid height或者正高,顾名思义就是指高于当地平均海平面的高度。我猜气压计测得的高度应当就是与海平面相关的。
- 椭球高。也称ellipsoid height或者大地高。顾名思义就是指相对于WGS84地球标准椭球模型的高度。GPS定位系统普遍采用的WGS84坐标系,给出的高度就是ellipsoid高度。
同一个位置的两种高度值一般可以相差几十米,这是因为当地平均海平面是和地形有关的,凹凸不平没有规律。而ellipsoid height采用的基准是地球标准椭球模型,它的高度值和地形没有关系,只和到地心的距离有关。
下文的mavros指ros1 noetic版本的,ros2版本的我还没研究。
Mavros
mavros/global_position/global话题
此话题发布经纬高,其中高度是ellipsoid height椭球高。其实px4的GLOBAL_POSITION_INT mavlink消息发布的高度是geoid height海拔高度,但是mavros做了转换后再发布到global话题,具体这个转换在:
template<typename MsgT>
inline void fill_lla(MsgT &msg, sensor_msgs::NavSatFix::Ptr fix)
{
fix->latitude = msg.lat / 1E7; // deg
fix->longitude = msg.lon / 1E7; // deg
fix->altitude = msg.alt / 1E3 + m_uas->geoid_to_ellipsoid_height(fix); // in meters
}
geoid_to_ellipsoid_height()就是海拔高转换为椭球高的函数。要进行这个转换,需要知道地球所有地点的平均海拔高,这是一个相当大的数据集。还记得安装mavros的时候需要执行一个install_geographiclib_datasets.sh脚本吗,其实这就是在安装egm96_5库,这个库存放了地球所有地点的平均海拔高模型,并提供每个经纬度点的海拔高和椭球高的差值。实测导入egm96_5库需要额外的18MB内存。
顺便一提,这个话题发布的经纬度只有七位小数精度,因为PX4的GLOBAL_POSITION_INT mavlink消息stream的时候,将经纬度乘了1e7变成了整型,mavros接收mavlink消息后再除了1e7,因此损失了经纬度七位小数之后的精度(大概相当于几厘米)。
下面这段c&#