gazebo中多架无人机仿真

目录

(一)运行多架无人机的仿真

(二)构建自己的world并在仿真中运行

(三)在gazebo中添加自己的model标签

(四)控制8架飞机简单飞行


(一)运行多架无人机的仿真

在multi_uav_mavros_sitl.launch中逐个添加uav,注意修改通讯和id,共涉及有以下4处修改:

  <arg name="ID" value="0"/>
        <arg name="fcu_url" default="udp://:14540@localhost:14580"/>
            <arg name="mavlink_udp_port" value="14560"/>
            <arg name="mavlink_tcp_port" value="4560"/>

运行如下指令

roslaunch px4 multi_uav_mavros_sitl.launch

(二)构建自己的world并在仿真中运行

进入:~/PX4-Autopilot/Tools/sitl_gazebo目录,在world文件夹中添加自己创建的world文件。

在multi_uav_mavros_sitl.launch中,将

<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"

中的empty.world替换为自己创建的world。

(三)在gazebo中添加自己的model标签

在主目录下打开隐藏文件夹,进入.gazebo目录。

如果没有models文件夹,先去git上下载。

将beer文件夹复制粘贴,修改为自己的标签名称;

将material文件夹中的textures文件夹中的png更换为自己的png,并删除beer.png;

将material文件夹中的scripts文件夹中的文件名称,修改为自己的名称,并将该文件中所涉及到beer的地方都修改为自己的标签名称;

将beer文件夹中的config和sdf文件中所涉及到beer的都更换为自己的标签。

(四)控制8架飞机简单飞行

以官网给出的一架飞机为例,进行添加

#include <ros/ros.h>
#include <geometry_msgs/PoseStamped.h>
#include <mavros_msgs/CommandBool.h>
#include <mavros_msgs/SetMode.h>
#include <mavros_msgs/State.h>

mavros_msgs::State current_state;
void state_cb(const mavros_msgs::State::ConstPtr& msg){
    current_state = *msg;
}

int main(int argc, char **argv)
{
    ros::init(argc, argv, "offb_node");

    //uav0
    ros::NodeHandle nh0;
    ros::Subscriber state_sub0 = nh0.subscribe<mavros_msgs::State>
            ("uav0/mavros/state", 10, state_cb);
    ros::Publisher local_pos_pub0 = nh0.advertise<geometry_msgs::PoseStamped>
            ("/uav0/mavros/setpoint_position/local", 10);
    ros::ServiceClient arming_client0 = nh0.serviceClient<mavros_msgs::CommandBool>
            ("/uav0/mavros/cmd/arming");
    ros::ServiceClient set_mode_client0 = nh0.serviceClient<mavros_msgs::SetMode>
            ("/uav0/mavros/set_mode");

    //uav1
    ros::NodeHandle nh1;
    ros::Subscriber state_sub1 = nh1.subscribe<mavros_msgs::State>
            ("uav1/mavros/state", 10, state_cb);
    ros::Publisher local_pos_pub1 = nh1.advertise<geometry_msgs::PoseStamped>
            ("/uav1/mavros/setpoint_position/local", 10);
    ros::ServiceClient arming_client1 = nh1.serviceClient<mavros_msgs::CommandBool>
            ("/uav1/mavros/cmd/arming");
    ros::ServiceClient set_mode_client1 = nh1.serviceClient<mavros_msgs::SetMode>
            ("/uav1/mavros/set_mode");

    //uav2
    ros::NodeHandle nh2;
    ros::Subscriber state_sub2 = nh2.subscribe<mavros_msgs::State>
            ("uav2/mavros/state", 10, state_cb);
    ros::Publisher local_pos_pub2 = nh2.advertise<geometry_msgs::PoseStamped>
            ("/uav2/mavros/setpoint_position/local", 10);
    ros::ServiceClient arming_client2 = nh2.serviceClient<mavros_msgs::CommandBool>
            ("/uav2/mavros/cmd/arming");
    ros::ServiceClient set_mode_client2 = nh2.serviceClient<mavros_msgs::SetMode>
            ("/uav2/mavros/set_mode");

    //uav3
    ros::NodeHandle nh3;
    ros::Subscriber state_sub3 = nh3.subscribe<mavros_msgs::State>
            ("uav3/mavros/state", 10, state_cb);
    ros::Publisher local_pos_pub3 = nh3.advertise<geometry_msgs::PoseStamped>
            ("/uav3/mavros/setpoint_position/local", 10);
    ros::ServiceClient arming_client3 = nh3.serviceClient<mavros_msgs::CommandBool>
            ("/uav3/mavros/cmd/arming");
    ros::ServiceClient set_mode_client3 = nh3.serviceClient<mavros_msgs::SetMode>
            ("/uav3/mavros/set_mode");

         //uav4
    ros::NodeHandle nh4;
    ros::Subscriber state_sub4 = nh4.subscribe<mavros_msgs::State>
            ("uav4/mavros/state", 10, state_cb);
    ros::Publisher local_pos_pub4 = nh4.advertise<geometry_msgs::PoseStamped>
            ("/uav4/mavros/setpoint_position/local", 10);
    ros::ServiceClient arming_client4 = nh4.serviceClient<mavros_msgs::CommandBool>
            ("/uav4/mavros/cmd/arming");
    ros::ServiceClient set_mode_client4 = nh4.serviceClient<mavros_msgs::SetMode>
            ("/uav4/mavros/set_mode");
      
         //uav5
    ros::NodeHandle nh5;
    ros::Subscriber state_sub5 = nh5.subscribe<mavros_msgs::State>
            ("uav5/mavros/state", 10, state_cb);
    ros::Publisher local_pos_pub5 = nh5.advertise<geometry_msgs::PoseStamped>
            ("/uav5/mavros/setpoint_position/local", 10);
    ros::ServiceClient arming_client5 = nh5.serviceClient<mavros_msgs::CommandBool>
            ("/uav5/mavros/cmd/arming");
    ros::ServiceClient set_mode_client5 = nh5.serviceClient<mavros_msgs::SetMode>
            ("/uav5/mavros/set_mode");      

         //uav6
    ros::NodeHandle nh6;
    ros::Subscriber state_sub6 = nh6.subscribe<mavros_msgs::State>
            ("uav6/mavros/state", 10, state_cb);
    ros::Publisher local_pos_pub6 = nh6.advertise<geometry_msgs::PoseStamped>
            ("/uav6/mavros/setpoint_position/local", 10);
    ros::ServiceClient arming_client6 = nh6.serviceClient<mavros_msgs::CommandBool>
            ("/uav6/mavros/cmd/arming");
    ros::ServiceClient set_mode_client6 = nh6.serviceClient<mavros_msgs::SetMode>
            ("/uav6/mavros/set_mode");

                  
         //uav7
    ros::NodeHandle nh7;
    ros::Subscriber state_sub7 = nh7.subscribe<mavros_msgs::State>
            ("uav7/mavros/state", 10, state_cb);
    ros::Publisher local_pos_pub7 = nh7.advertise<geometry_msgs::PoseStamped>
            ("/uav7/mavros/setpoint_position/local", 10);
    ros::ServiceClient arming_client7 = nh7.serviceClient<mavros_msgs::CommandBool>
            ("/uav7/mavros/cmd/arming");
    ros::ServiceClient set_mode_client7 = nh7.serviceClient<mavros_msgs::SetMode>
            ("/uav7/mavros/set_mode");



    //the setpoint publishing rate MUST be faster than 2Hz
    ros::Rate rate(20.0);

    // wait for FCU connection
    while(ros::ok() && !current_state.connected){
        ros::spinOnce();
        rate.sleep();
    }
    // x_num, y_num  refer to the desired uav input position
    //all the uavs have the same height : z

    float x0 = 0.0, y0 = 0.0;
    float x1 = 1.0, y1 = 0.0;
    float x2 = 2.0, y2 = 0.0;
    float x3 = 3.0, y3 = 0.0;
    float x4 = 0.0, y4 = 1.0;
    float x5 = 1.0, y5 = 1.0;
    float x6 = 2.0, y6 = 1.0;
    float x7 = 3.0, y7 = 1.0;

    float z = 2.0;
    float w = 0.0;
    const float pi = 3.1415926;
    geometry_msgs::PoseStamped pose0;
    geometry_msgs::PoseStamped pose1;
    geometry_msgs::PoseStamped pose2;
    geometry_msgs::PoseStamped pose3;
    geometry_msgs::PoseStamped pose4;
    geometry_msgs::PoseStamped pose5;
    geometry_msgs::PoseStamped pose6;
     geometry_msgs::PoseStamped pose7;

    pose0.pose.position.x = x0;
    pose0.pose.position.y = y0;
    pose0.pose.position.z = z;
    pose1.pose.position.x = x1;
    pose1.pose.position.y = y1;
    pose1.pose.position.z = z;
    pose2.pose.position.x = x2;
    pose2.pose.position.y = y2;
    pose2.pose.position.z = z;
    pose3.pose.position.x = x3;
    pose3.pose.position.y = y3;
    pose3.pose.position.z = z;
    pose4.pose.position.x = x4;
    pose4.pose.position.y = y4;
    pose4.pose.position.z = z;
    pose5.pose.position.x = x5;
    pose5.pose.position.y = y5;
    pose5.pose.position.z = z;
    pose6.pose.position.x = x6;
    pose6.pose.position.y = y6;
    pose6.pose.position.z = z;    
    pose7.pose.position.x = x7;
    pose7.pose.position.y = y7;
    pose7.pose.position.z = z;
    //uavs have the initial position offset because of the .launch config file
    float x0_offset = -3;
    float x1_offset = -1;
    float x2_offset = 1;
    float x3_offset = 3;

    //define uavs' coordinates in the formation coordinate system
    float x0_f = -0.5, y0_f = 0.5;
    float x1_f = 0.5, y1_f = 0.5;
    float x2_f = -0.5, y2_f = -0.5;
    float x3_f = 0.5, y3_f = -0.5;
    float xx, yy;

    //send a few setpoints before starting
    for(int i = 100; ros::ok() && i > 0; --i){
        local_pos_pub0.publish(pose0);
        local_pos_pub1.publish(pose1);
        local_pos_pub2.publish(pose2);
        local_pos_pub3.publish(pose3);
        local_pos_pub3.publish(pose4);
        local_pos_pub3.publish(pose5);
        local_pos_pub3.publish(pose6);
        local_pos_pub3.publish(pose7);
        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 = ros::Time::now();

    while(ros::ok()){
        if( current_state.mode != "OFFBOARD" &&
            (ros::Time::now() - last_request > ros::Duration(5.0))){

            if( set_mode_client0.call(offb_set_mode) &&
                set_mode_client1.call(offb_set_mode) &&
                set_mode_client2.call(offb_set_mode) &&
                set_mode_client3.call(offb_set_mode) &&
                set_mode_client4.call(offb_set_mode) &&
                set_mode_client5.call(offb_set_mode) &&
                set_mode_client6.call(offb_set_mode) &&
                set_mode_client7.call(offb_set_mode) &&
                offb_set_mode.response.mode_sent){
                ROS_INFO("Offboard enabled : 8");
            }
            last_request = ros::Time::now();
        } else {
            if( !current_state.armed &&
                (ros::Time::now() - last_request > ros::Duration(5.0))){
                if( arming_client0.call(arm_cmd) &&
                    arming_client1.call(arm_cmd) &&
                    arming_client2.call(arm_cmd) &&
                    arming_client3.call(arm_cmd) &&
                    arming_client4.call(arm_cmd) &&
                    arming_client5.call(arm_cmd) &&
                    arming_client6.call(arm_cmd) &&
                    arming_client7.call(arm_cmd) &&
                    arm_cmd.response.success){
                    ROS_INFO("Vehicle armed : 8");

                }
                last_request = ros::Time::now();
            }
        }

        local_pos_pub0.publish(pose0);
        local_pos_pub1.publish(pose1);
        local_pos_pub2.publish(pose2);
        local_pos_pub3.publish(pose3);
        local_pos_pub4.publish(pose4);
        local_pos_pub5.publish(pose5);
        local_pos_pub6.publish(pose6);
        local_pos_pub7.publish(pose7);

        w = w + 2*pi/(30/(1/20.0));
        if(w > 2*pi){
            w = w - 2*pi;
        }
        xx = 4.75*cos(w);
        yy = 4.75*sin(w);

        x0 = x0_f*cos(w) - y0_f*sin(w) + xx - x0_offset;
        y0 = y0_f*cos(w) + x0_f*sin(w) + yy;
        pose0.pose.position.x = x0;
        pose0.pose.position.y = y0;

        x1 = x1_f*cos(w) - y1_f*sin(w) + xx - x1_offset;
        y1 = y1_f*cos(w) + x1_f*sin(w) + yy;
        pose1.pose.position.x = x1;
        pose1.pose.position.y = y1;

        x2 = x2_f*cos(w) - y2_f*sin(w) + xx - x2_offset;
        y2 = y2_f*cos(w) + x2_f*sin(w) + yy;
        pose2.pose.position.x = x2;
        pose2.pose.position.y = y2;

        x3 = x3_f*cos(w) - y3_f*sin(w) + xx - x3_offset;
        y3 = y3_f*cos(w) + x3_f*sin(w) + yy;
        pose3.pose.position.x = x3;
        pose3.pose.position.y = y3;

        pose4.pose.position.x = x0;
        pose4.pose.position.y = y0;
        pose5.pose.position.x = x0;
        pose5.pose.position.y = y0;
        pose6.pose.position.x = x0;
        pose6.pose.position.y = y0;
        pose7.pose.position.x = x0;
        pose7.pose.position.y = y0;
        ros::spinOnce();
        rate.sleep();
    }

    return 0;
}

rosrun 这个节点,即可看到8架飞机在仿真中绕圆。

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值