基于gazebo和mavros实现两台无人机的位姿跟踪实验(使用GPS数据)

概要:使用gps数据,实现uav0跟踪uav1的位置与方向功能,方法如下:

  • 位置跟踪:订阅global_position/global的经纬高信息
  • 方向跟踪:订阅global_position/compass_hdg的航向信息

1. 位置跟踪

1.1. 获取经度、纬度

订阅无人机0号的global_position/global 话题,消息类型为 sensor_msgs/NavSatFix Message 类型,直接使用其中的经度、纬度数据。

在这里插入图片描述

1.2. 获取高度

高度数据不能直接用于发布,Mavros官方文档提到:

  • 使用 setpoint_position/global 指定的高度是相对于平均海平面(AMSL)的高度。但是global_position/global感知的高度是相对于WGS-84椭球体的高度。
  • MAVROS使用GeographicLib库来将AMSL高度转换为椭球体高度。从AMSL高度转换为椭球体高度时,需要加上大地水准面分离值。

因此:AMSL高度 = 椭球体高度 - 大地水准面分离值,也就是将订阅到的高度减去一个差值,才得到要发布的高度。该值可以使用GeographicLib提供的geoid函数,用指定的纬度和经度来计算大地水准面分离值。

至此,得到了要发布的经度、纬度、高度数据。

    pose_uav1_global.pose.position.latitude = msg->latitude;
    pose_uav1_global.pose.position.longitude = msg->longitude;  
    
    GeographicLib::Geoid geoid("egm96-5", "", true, true);
    double geoid_height = geoid(msg->latitude, msg->longitude);  // 获取大地水准面分离值        
    pose_uav1_global.pose.position.altitude = msg->altitude - geoid_height + 1.0; // 将椭球体高度转换为AMSL高度

2. 方向跟踪

2.1. 获取航向角

订阅 global_position/compass_hdg 话题,消息类型为 std_msgs/Float64,是无人机相对于NED坐标系的航向角(heading)。该角度不能直接用于发布,原因如下:

  • global_position/compass_hdg 的航向角是基于NED坐标系的(北东地)
  • setpoint_position/global 的四元数姿态是基于ENU坐标系的(东北天)
  • 由于NED和ENU坐标系的差异,在将NED坐标系下的航向角应用到ENU坐标系时,需要进行转换。
    在这里插入图片描述

从坐标系定义中,可以看出,ENU和NED的坐标变换关系是:
X(ENU) = Y(NED)
Y(ENU) = X(NED)
Z(ENU) = - Z(NED)
Yaw(ENU) = 90 - Yaw(NED)

可得,要转到同一个方向,NED中的Yaw角和ENU中的Yaw角互余。

2.2. 转成四元数

将航向角从NED坐标系转到ENU坐标系后,将角度转成弧度,再通过 setRPY() 函数转成四元数。

至此,得到了要发布的姿态角数据。

    tf2::Quaternion q;
    double corrected_heading = 90.0 - uav0_heading; //两个坐标系的 Yaw 角互余
    if (corrected_heading < 0) corrected_heading += 360.0;  // 保持在[0, 360)范围内
    q.setRPY(0, 0, corrected_heading * M_PI / 180.0); // 转换为弧度并计算四元数
    pose_uav1_global.pose.orientation.x = q.x();
    pose_uav1_global.pose.orientation.y = q.y();
    pose_uav1_global.pose.orientation.z = q.z();
    pose_uav1_global.pose.orientation.w = q.w();

2.3. 发布

上述步骤得到了经度、纬度、高度、航向角,现在通过无人机1号的 setpoint_position/global 话题发布,消息类型为 geographic_msgs/GeoPoseStamped。

注意:

  • setpoint_position/global的消息类型为geographic_msgs/GeoPoseStamped
  • setpoint_position/local的消息类型为geometry_msgs/PoseStamped
  • 前者的位置由latitude、longitude、altitude组成,后者的位置由x、y、z组成,两者的方向都用四元数表示。

3. ROS程序

#include <ros/ros.h>
#include <mavros_msgs/CommandBool.h>
#include <mavros_msgs/SetMode.h>
#include <mavros_msgs/State.h>
#include <sensor_msgs/NavSatFix.h>
#include <geographic_msgs/GeoPoseStamped.h>
#include <GeographicLib/Geoid.hpp>
#include <std_msgs/Float64.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Matrix3x3.h>

mavros_msgs::State current_state_uav1;
geographic_msgs::GeoPoseStamped pose_uav1_global;
double uav0_heading = 0.0;

void state_cb_uav1(const mavros_msgs::State::ConstPtr& msg){
    current_state_uav1 = *msg;
}

void pose_update_cb(const sensor_msgs::NavSatFix::ConstPtr& msg) { 
    pose_uav1_global.pose.position.latitude = msg->latitude;
    pose_uav1_global.pose.position.longitude = msg->longitude;

    // 使用 GeographicLib 进行椭球体高度到 AMSL 的转换    
    GeographicLib::Geoid geoid("egm96-5", "", true, true);
    double geoid_height = geoid(msg->latitude, msg->longitude);  // 获取大地水准面分离值        
    pose_uav1_global.pose.position.altitude = msg->altitude - geoid_height + 1.0; // 将椭球体高度转换为AMSL高度

    // 设置方向,使用来自uav0的航向信息
    tf2::Quaternion q;
    double corrected_heading = (uav0_heading - 90.0) * -1.0;  // 修正航向角
    if (corrected_heading < 0) corrected_heading += 360.0;  // 保持在[0, 360)范围内
    ROS_INFO("convert to: %f rad", corrected_heading * M_PI / 180.0);
    q.setRPY(0, 0, corrected_heading * M_PI / 180.0); // 将航向从度转换为弧度
    pose_uav1_global.pose.orientation.x = q.x();
    pose_uav1_global.pose.orientation.y = q.y();
    pose_uav1_global.pose.orientation.z = q.z();
    pose_uav1_global.pose.orientation.w = q.w();
}

void heading_update_cb(const std_msgs::Float64::ConstPtr& msg) {
    uav0_heading = msg->data;
}

int main(int argc, char **argv)
{
    ros::init(argc, argv, "uav1_node");
    ros::NodeHandle nh;
    ros::Subscriber state_sub_uav1 = nh.subscribe<mavros_msgs::State>
            ("uav1/mavros/state", 10, state_cb_uav1);
    ros::Publisher global_pos_pub_uav1 = nh.advertise<geographic_msgs::GeoPoseStamped>
            ("uav1/mavros/setpoint_position/global", 10);
    ros::Subscriber pose_sub = nh.subscribe<sensor_msgs::NavSatFix>
            ("uav0/mavros/global_position/global", 10, pose_update_cb);
    ros::Subscriber heading_sub = nh.subscribe<std_msgs::Float64>
        ("uav0/mavros/global_position/compass_hdg", 10, heading_update_cb);        
    ros::ServiceClient arming_client_uav1 = nh.serviceClient<mavros_msgs::CommandBool>
            ("uav1/mavros/cmd/arming");
    ros::ServiceClient set_mode_client_uav1 = nh.serviceClient<mavros_msgs::SetMode>
            ("uav1/mavros/set_mode");

    ros::Rate rate(20.0);

    // Wait for FCU connection
    while (ros::ok() && (!current_state_uav1.connected)) {
        ros::spinOnce();
        rate.sleep();
    }

    pose_uav1_global.pose.position.latitude = 0;
    pose_uav1_global.pose.position.longitude = 0;
    pose_uav1_global.pose.position.altitude = 2.0;
    pose_uav1_global.pose.orientation.w = 0.0;
    pose_uav1_global.pose.orientation.x = 0.0;
    pose_uav1_global.pose.orientation.y = 0.0;
    pose_uav1_global.pose.orientation.z = 0.0;

    for (int i = 100; ros::ok() && i > 0; --i) {
        global_pos_pub_uav1.publish(pose_uav1_global);
        ros::spinOnce();
        rate.sleep();
    }

    mavros_msgs::SetMode offb_set_mode;
    offb_set_mode.request.custom_mode = "OFFBOARD";

    mavros_msgs::CommandBool arm_cmd;
    arm_cmd.request.value = true;

    ros::Time last_request_uav1 = ros::Time::now();

    while (ros::ok()) {
        // 检查并设置uav1的OFFBOARD模式和解锁状态
        if (current_state_uav1.mode != "OFFBOARD" &&
            (ros::Time::now() - last_request_uav1 > ros::Duration(1.0))) {
            if (set_mode_client_uav1.call(offb_set_mode) &&
                offb_set_mode.response.mode_sent) {
                ROS_INFO("Offboard enabled for uav1");
            }
            last_request_uav1 = ros::Time::now();
        } else {
            if (!current_state_uav1.armed &&
                (ros::Time::now() - last_request_uav1 > ros::Duration(1.0))) {
                if (arming_client_uav1.call(arm_cmd) &&
                    arm_cmd.response.success) {
                    ROS_INFO("uav1 armed");
                }
                last_request_uav1 = ros::Time::now();
            }
        }

        global_pos_pub_uav1.publish(pose_uav1_global); // 发布目标
        ros::spinOnce();
        rate.sleep();        
    }

    return 0;
}

4. 演示视频

uav1根据GPS信号跟踪uav0的位置与方向

5. 问题记录

5.1. 指定高度和实际高度不一致

  • 问题:飞行时,发现uav1的setpoint_position符合预期,但是实际的global_position与前者并不相等。
  • 原因:使用 setpoint_position/global 指定的高度是相对于平均海平面(AMSL)的高度,但是global_position/global感知的高度是相对于WGS-84椭球体的高度,两者需要进行转换。
  • 解决方法:要设定的高度 = 测量到的高度 - 大地水准面分离值,该值可以使用GeographicLib提供的geoid函数,用指定的纬度和经度来计算大地水准面分离值。

5.2. uav1和uav0的朝向角相差90度

5.3. 欧拉角、四元数、旋转矩阵的转换

  • 问题:对三个概念不清晰。
    在这里插入图片描述
  • 欧拉角:在某种情况下会遇到万向锁问题,即会丢失一个自由度的信息。
  • 旋转矩阵:便于表示多次旋转,但里面有九个数值,而三维旋转一次只需要三个自由度,存储和计算量大。
  • 四元数:没有欧拉角的万向锁问题,比旋转矩阵的计算开销小,所以四元数表示姿态应用较多,缺点是不够直观。

参考文章
欧拉角、旋转矩阵及四元数
三维几何中的旋转表示:四元数、欧拉角和旋转矩阵
一文详解四元数、欧拉角、旋转矩阵、轴角如何相互转换

6. 调试工具

6.1. rosbag——录制与回放话题

rosbag是用于录制和回放 ROS 主题的一个工具集,本质也是ros的节点,可以使用命令行或者编码实现。

录制时,rosbag是一个订阅者,可以订阅到的话题消息写入磁盘文件。
回放时,rosbag是一个发布者,可以读取磁盘文件,发布文件中的话题消息。

  • 命令行实现
录制所有话题:rosbag record -a -O 目标文件名
录制特定话题:rosbag record -O 目标文件名 /uav1/pose /uav0/pose

回放文件:rosbag play 目标文件名
控制回放速度,以2倍速为例:rosbag play -r 2 目标文件名
指定开始时间,以第10s开始为例:rosbag play -s 10 目标文件名
回放特定话题:rosbag play 目标文件名 /uav1/pose
  • 编码实现
//写 bag文件:
#include "ros/ros.h"
#include "rosbag/bag.h"
#include "std_msgs/String.h"

int main(int argc, char *argv[])
{
    ros::init(argc,argv,"bag_write");
    ros::NodeHandle nh;
    //创建 bag 对象
    rosbag::Bag bag;
    //打开
    bag.open("/home/rosdemo/demo/test.bag",rosbag::BagMode::Write);
    //写
    std_msgs::String msg;
    msg.data = "hello world";
    bag.write("/chatter",ros::Time::now(),msg);
    bag.write("/chatter",ros::Time::now(),msg);
    bag.write("/chatter",ros::Time::now(),msg);
    bag.write("/chatter",ros::Time::now(),msg);
    //关闭
    bag.close();

    return 0;
}
// 读 bag 文件:
#include "ros/ros.h"
#include "rosbag/bag.h"
#include "rosbag/view.h"
#include "std_msgs/String.h"
#include "std_msgs/Int32.h"

int main(int argc, char *argv[])
{

    setlocale(LC_ALL,"");

    ros::init(argc,argv,"bag_read");
    ros::NodeHandle nh;

    //创建 bag 对象
    rosbag::Bag bag;
    //打开 bag 文件
    bag.open("/home/rosdemo/demo/test.bag",rosbag::BagMode::Read);
    //读数据
    for (rosbag::MessageInstance const m : rosbag::View(bag))
    {
        std_msgs::String::ConstPtr p = m.instantiate<std_msgs::String>();
        if(p != nullptr){
            ROS_INFO("读取的数据:%s",p->data.c_str());
        }
    }

    //关闭文件流
    bag.close();
    return 0;
}

6.2. PlotJuggler——绘制曲线图

本实验采用PlotJuggler分析两种不同格式的数据,即ROS bag文件(.bag格式)和QGroundControl (QGC) 地面站保存的日志文件 (.ulg 格式)。

  • bag文件是ROS中用于记录和回放话题数据的格式,包含了Mavros的传感器数据、控制指令、状态信息等。
  • ulg文件是PX4飞控系统使用的日志格式,由QGroundControl (QGC) 生成,记录了飞控系统的详细运行情况,包括传感器读数、执行的控制指令、状态估计等。

1. 软件安装(ROS_DISTRO是自己的ROS版本)

sudo apt install ros-${ROS_DISTRO}-plotjuggler-ros

2. 软件运行

rosrun plotjuggler plotjuggler

3. 验证位置跟踪效果

将飞控日志的vehicle_global_position数据、rosbag录制的global_position/global数据,导入PlotJuggler进行分析,由于时间戳对齐,可以直接进行比较。经度和纬度数据一致,高度相差了47m左右,此数值就是上文提到的大地水准面分离值,将测量高度 - 大地水准面分离值,得到的设定值才可以发送给飞控。由图可知,uav1跟踪uav0的经度、纬度,高度保持在uav0的上空1米。
在这里插入图片描述

4. 验证方向跟踪效果

将飞控日志的vehicle_global_position/yaw数据、rosbag录制的global_position/compass_hdg数据,导入PlotJuggler进行分析,左侧图像是弧度制,范围为[-3.14,3.14];右侧图像是角度值,范围为[0,360]。如果将左侧图像取绝对值,曲线形状将和右侧图像一致。

由图可知,uav1跟踪uav0的航向角。
在这里插入图片描述

6.3. Foxglove——更详细的可视化

Foxglove 与 PlotJuggler 都可以绘制曲线图,而 Foxglove 提供了更多的可视化选项,主要包含各种panel面板,以下对它比较独特的面板进行介绍。

1. Diagnostics 诊断
显示来自源中的 ROS 主题消息的已看到节点的状态(即陈旧、错误、警告或正常),如下图能实时回看飞控的电量、GPS信息、心跳包等。
在这里插入图片描述

2. Map 地图
在世界地图上显示 GPS 数据,对于ROS1支持的数据类型是sensor_msgs/NavSatFix,与global_position/global话题的类型一致。

下图是加载bag文件,查看无人机的全程飞行轨迹(飞了一个风筝形状),飞行轨迹上的点,可以和曲线图的点一一对应,可以点击查看源数据。
在这里插入图片描述

3. Raw messages 原生数据
除了能绘制曲线图以外,还能实时看到话题的原始数据。
在这里插入图片描述

4. 在线数据流
除了加载录制好的文件以外,可以通过 Rosbridge 与 ROS Master 连接,获取实时数据,步骤如下。

  1. 启动Rosbridge服务;

    roslaunch rosbridge_server rosbridge_websocket.launch
    
  2. 在 Foxglove Studio 中选择 Rosbridge 连接选项;

  3. 输入 WebSocket 服务器的 URL,端口号默认为9090。
    在这里插入图片描述

5. 综合功能演示
使用 Foxglove 的实时数据流、地图、曲线图、原生数据等功能,对飞行过程进行实时监控,此次飞行轨迹为一个风筝形状,其中uav0为红色点,uav1为蓝色点。

使用Foxglove实时监控飞行过程

PX4无人机以及Gazebo仿真环境是目前广泛使用无人机软件和仿真平台,能够帮助开发者进行无人机飞行控制算法的开发和测试。在使用PX4和Gazebo进行仿真时,可以通过编写代码实现无人机跟踪移动物体的功能。 首先,需要在Gazebo仿真环境中创建一个场景,并将无人机和移动物体添加到场景中。可以使用Gazebo自带的模型库或者自定义模型来创建无人机和移动物体。然后,将无人机Gazebo和PX4进行连接,以便将无人机的状态信息传输到Gazebo仿真环境中。 其次,需要编写代码来实现无人机对移动物体的跟踪。首先,需要获取无人机和移动物体的位置信息。可以通过Gazebo提供的API或者PX4提供的功能来获取无人机和移动物体的位置。然后,根据无人机和移动物体的位置信息,计算出无人机需要采取的飞行姿态和动作来实现跟踪移动物体的功能。最后,通过控制无人机的舵面、电机等飞行控制设备,实现无人机的飞行动作。 在跟踪移动物体的过程中,还可以添加一些算法来提高跟踪的准确性和稳定性。例如,可以使用视觉传感器来实时识别和跟踪移动物体,通过视觉算法和控制算法来控制无人机的飞行动作。另外,还可以使用数据融合算法,将无人机的惯性传感器数据和视觉传感器数据进行融合,提高跟踪的鲁棒性和精确性。 综上所述,通过在Gazebo仿真环境中使用PX4无人机,可以实现对移动物体的跟踪。通过获取无人机和移动物体的位置信息,并根据位置信息计算出无人机的飞行动作,以实现跟踪移动物体的功能。同时,还可以添加一些算法来提高跟踪的准确性和稳定性。
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值