< >
Home » PX4与仿真入门教程 » PX4与仿真入门教程-dronedoc-offboard控制例子(cpp)

PX4与仿真入门教程-dronedoc-offboard控制例子(cpp)

PX4与仿真入门教程-dronedoc-offboard控制例子(cpp)

说明:

  • 介绍如何在 C++ 中创建一个 ROS 节点,以在模拟上操作无人机

步骤:

  • 创建一个 ROS 包来存储您自己的节点。包名称为 px4_sim_pkg。
  • 由于使用了 roscpp、roscpp、geometry_msgs 和 mavros_msgs 包,将它们添加到依赖包中
cd ~/dronedoc_ws/src
catkin_create_pkg px4_sim_pkg roscpp rospy geometry_msgs mavros_msgs std_msgs
vim px4_sim_pkg/src/offboard_sample.cpp
  • 内容如下:
/**
 * @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 <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");
    ros::NodeHandle nh;

    ros::Subscriber state_sub = nh.subscribe<mavros_msgs::State>
            ("mavros/state", 10, state_cb);
    ros::Publisher local_pos_pub = nh.advertise<geometry_msgs::PoseStamped>
            ("mavros/setpoint_position/local", 10);
    ros::ServiceClient arming_client = nh.serviceClient<mavros_msgs::CommandBool>
            ("mavros/cmd/arming");
    ros::ServiceClient set_mode_client = nh.serviceClient<mavros_msgs::SetMode>
            ("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;
}
  • 编辑CMakeLists.txt文件
cd ~/dronedoc_ws/src/
vim px4_sim_pkg/CMakeLists.txt
  • 在最后添加如下内容:
add_executable(offboard_sample src/offboard_sample.cpp)
target_link_libraries(offboard_sample ${catkin_LIBRARIES})
  • 编译包
cd ~/dronedoc_ws/
catkin_make
  • 添加到环境变量,增加到第一行
sed -i '1i\source ~/dronedoc_ws/devel/setup.bash' ~/tools/dronedoc/load_environment.sh
  • 编写luanch文件
  • 进入目录包目录新建文件
mkdir ~/dronedoc_ws/src/px4_sim_pkg/launch
cd ~/dronedoc_ws/src/px4_sim_pkg/launch
vim cpp_offb_sample.launch
  • 内容如下:
<launch>

    <include file="$(find px4)/launch/mavros_posix_sitl.launch" />
    <node name="offb_node" pkg="px4_sim_pkg" type="offboard_sample" />

</launch>

测试:

  • 新终端,启动模拟器和起飞
cd ~/tools/dronedoc/
source load_environment.sh
roslaunch px4_sim_pkg cpp_offb_sample.launch
  • 效果如下:

请输入图片描述

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: px4与仿真入门教程