代码拉取完成,页面将自动刷新
飞机起飞前,不停刷新home点位置(可通过/mavros/home_position/home读取),该点位置和/mavros/local_position/pose历史位置数据一样,而不是/mavros/global_position/local话题,也就是说home点坐标是基于/mavros/local_position/pose话题的。因此要返航可以直接发布mavros/setpoint_raw/local话题,给出home点坐标即可。
void command_to_mavros::idle()
{
mavros_msgs::PositionTarget pos_setpoint;
//Here pls ref to mavlink_receiver.cpp
pos_setpoint.type_mask = 0x4000;
setpoint_raw_local_pub.publish(pos_setpoint);
}
0x4000代表怠速
0x1000代表起飞 ##这个好像不好用
0x2000代表降落 ##这个好像不好用
0x3000代表游荡 ##这个好像不好用
<plugin name='gps_plugin' filename='libgazebo_gps_plugin.so'>
<robotNamespace/>
<gpsNoise>1</gpsNoise>
</plugin>
<gpsSubTopic>/gps</gpsSubTopic>
此处可能存在不合适展示的内容,页面不予展示。您可通过相关编辑功能自查并修改。
如您确认内容无涉及 不当用语 / 纯广告导流 / 暴力 / 低俗色情 / 侵权 / 盗版 / 虚假 / 无价值内容或违法国家有关法律法规的内容,可点击提交进行申诉,我们将尽快为您处理。