PX4 Offboard Control with MAVROS--Takeoff(一键起飞)

警告:请先在仿真环境下进行测试,能达到预期效果后在进行实际飞行测试,以免发生意外。本篇文章只是用作学习交流,实际飞行时如出现意外情况作者不予以负责。

所需材料

———————————————————————————————————————————

1、PIXhawk或者Pixracer

2、能够运行MAVROS的树莓派3B

3、一根micro USB 数据线

———————————————————————————————————————————

 在上一个片文章当中介绍了如何搭建ROS系统,并且运行MAVROS包来监听一个飞控消息,本篇文章将讨论如何使用MAVROS来控制无人机进行一键起飞功能。

一、创建一个offboard节点

1、在/catkin_ws/src目录中创建一个新的offb_node.cpp文件

roscd px4_mavros/src
vim offb_node.cpp

2、写入控制代码

 参考官网给出的历程

/**
 * @file offb_node.cpp
 * @brief Offboard control example node, written with MAVROS version 0.19.x, PX4 Pro Flight
 * Stack and tested in Gazebo SITL
 */

#include 
#include 
#include 
#include 
#include 

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");
    ros::NodeHandle nh;

    ros::Subscriber state_sub = nh.subscribe
            ("mavros/state", 10, state_cb);
    ros::Publisher local_pos_pub = nh.advertise
            ("mavros/setpoint_position/local", 10);
    ros::ServiceClient arming_client = nh.serviceClient
            ("mavros/cmd/arming");
    ros::ServiceClient set_mode_client = nh.serviceClient
            ("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();
    }

    geometry_msgs::PoseStamped pose;
    pose.pose.position.x = 0;
    pose.pose.position.y = 0;
    pose.pose.position.z = 2;

    //send a few setpoints before starting
    for(int i = 100; ros::ok() && i > 0; --i){
        local_pos_pub.publish(pose);
        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_client.call(offb_set_mode) &&
                offb_set_mode.response.mode_sent){
                ROS_INFO("Offboard enabled");
            }
            last_request = ros::Time::now();
        } else {
            if( !current_state.armed &&
                (ros::Time::now() - last_request > ros::Duration(5.0))){
                if( arming_client.call(arm_cmd) &&
                    arm_cmd.response.success){
                    ROS_INFO("Vehicle armed");
                }
                last_request = ros::Time::now();
            }
        }

        local_pos_pub.publish(pose);

        ros::spinOnce();
        rate.sleep();
    }

    return 0;
}

3、编辑CMakeLists.txt文件

rosed px4_mavros CMakeLists.txt
加入一下代码:

add_executable(offb_node src/offb_node.cpp)

target_link_libraries(offb_node ${catkin_LIBRARIES})

4、编译源码

cd ~/catkin_ws
catkin_make

二、运行offboard节点

警告:在进行下面操作前请将螺旋桨摘除再进行测试,避免误伤。

1、运行启动文件

roslaunch mavros px4.launch

2、启动按钮解锁

 长按启动爱开关进行解锁操作。

PX4 Offboard Control with MAVROS--Takeoff(一键起飞)_第1张图片

3、运行节点

 如果有仿真环境,则可以看到飞行器缓缓升高,直至保持在一个高度。

rosrun px4_mavros offb_node


—————————————————————END———————————————————


参考文章:

https://dev.px4.io/en/ros/mavros_offboard.html









你可能感兴趣的:(MAVROS)