PX4 Offboard Control Using MAVROS on Gazebo


PX4 Offboard Control Using MAVROS on Gazebo

最近在学习PX4和mavros,感觉px4官网的教程总体上讲得不错,但有一些地方不是很友好,比如offboard control这一块儿,讲的比较简单,省略了gazebo的使用,我上网查了一大堆资料才勉强把这个示例代码在gazebo中跑出来。所以这里做一个记录,希望对看到的人有点帮助。

安装MAVROS

介绍安装mavros的两种方式,建议参考:ROS with MAVROS Installation Guide

方法一:二进制安装 (Debian / Ubuntu)

ROS 存储库包含适用于 Ubuntu x86、amd64 (x86_64) 和 armhf (ARMv7) 的二进制包。Kinetic 还支持 Debian Jessie amd64 和 arm64 (ARMv8)。

使用apt-get安装:

sudo apt-get install ros-melodic-mavros ros-melodic-mavros-extras

然后安装GeographicLib通过运行install_geographiclib_datasets.sh脚本获取数据集:

wget https://raw.githubusercontent.com/mavlink/mavros/master/mavros/scripts/install_geographiclib_datasets.sh
sudo bash ./install_geographiclib_datasets.sh   

方法二:源码安装

此安装假定您有一个 catkin 工作区位于~/catkin_ws如果您不使用以下内容创建一个:

mkdir -p ~/catkin_ws/src
cd ~/catkin_ws
catkin init
wstool init src

您将使用 ROS Python 工具:wstool(用于检索源)、rosinstallcatkin_tools(构建)进行此安装。虽然它们可能是在您安装 ROS 期间安装的,但您也可以通过以下方式安装它们:

sudo apt-get install python-catkin-tools python-rosinstall-generator -y

虽然可以使用catkin_make构建包,但首选方法是使用catkin_tools,因为它是一种更通用且“友好”的构建工具。

如果这是您第一次使用 wstool,则需要使用以下命令初始化源空间:

wstool init ~/catkin_ws/src

现在您已准备好进行构建

  1. 安装 MAVLink;

    # We use the Kinetic reference for all ROS distros as it's not distro-specific and up to date
    rosinstall_generator --rosdistro kinetic mavlink | tee /tmp/mavros.rosinstall
  2. 使用已发布或最新版本从源代码安装 MAVROS;

    • 发行版 / 稳定版

      rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall
    • 最新源码

      rosinstall_generator --upstream-development mavros | tee -a /tmp/mavros.rosinstall
      # For fetching all the dependencies into your catkin_ws, 
      # just add '--deps' to the above scripts, E.g.:
      #   rosinstall_generator --upstream mavros --deps | tee -a /tmp/mavros.rosinstall
  3. 创建工作区 & 安装依赖;

    wstool merge -t src /tmp/mavros.rosinstallwstool update -t src -j4rosdep install --from-paths src --ignore-src -y
  4. 安装 GeographicLib数据集;

    ./src/mavros/mavros/scripts/install_geographiclib_datasets.sh
  5. 构建;

    catkin build
  6. 确保您使用工作区中的 setup.bash 或 setup.zsh。

    #Needed or rosrun can't find nodes from this workspace.
    source devel/setup.bash

出现错误的情况下,mavros repo还有额外的安装和故障排除说明。

构建offboard control示例程序

这里介绍构建官网示例代码的步骤,代码解读请参考:MAVROS Offboard control example

进入你的工作区并且创建一个包:

cd ~/catkin_ws/src
catkin_create_pkg offboard_pkg roscpp std_msgs geometry_msgs mavros_msgs

在目录~/catkin_ws/src/offboard_pkg/src/中,新建一个文件offboard_node.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;
}

然后打开目录~/catkin_ws/src/offboard_pkg/下的CMakeLists.txt添加下面的两行:

add_executable(offboard_node src/offboard_node.cpp)
target_link_libraries(offboard_node ${catkin_LIBRARIES})

然后到目录~/catkin_ws下,运行命令,完成编译:

catkin_make

之后你可以在~.bashrc或者~.zshrc中写入source该工作空间的指令,如果出现了工作空间覆盖的问题,可以参考我的另外一篇博客解决source多个ROS工作空间时的覆盖问题

安装PX4-Autopilot

网上有一些教程讲的是Firmware,但两个应该都是一样的。

下载PX4-Autopilot

git clone https://github.com/PX4/PX4-Autopilot.git
cd PX4-Autopilot
git checkout v1.12.0

编译PX4-Autopilot

make distclean
make px4_sitl_default gazebo

请确保make px4_sitl_default gazebo命令执行成功,如有报错信息,根据报错信息来进行修复即可。

在这条指令运行成功之后,gazebo会打开,你会看到如下的界面:

修改~.bashrc或者~.zshrc(optional)

这一步不影响我们在gazebo中运行Offboard Control示例程序,但还是建议修改一下。

source ~/PX4-Autopilot/Tools/setup_gazebo.bash ~/PX4-Autopilot ~/PX4-Autopilot/build/px4_sitl_defaultexport
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:~/PX4-Autopilotexport
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:~/PX4-Autopilot/Tools/sitl_gazebo

在Gazebo中运行Offboard Control示例程序

启动Gazebo

像之前一样,进入到PX4-Autopilot的目录中,运行如下指令打开Gazebo:

make px4_sitl_default gazebo

运行MAVROS

mavlink会开放14557, 接到这个端口将会接收到实际飞行中发出的所有数据。

若要连接到一个特定的IP(fcu_url是SITL的IP/端口),请使用一个如下形式的URL:

roslaunch mavros px4.launch fcu_url:="udp://:14540@192.168.1.36:14557"

连接本地:

roslaunch mavros px4.launch fcu_url:="udp://:14540@127.0.0.1:14557"

这里我们在自己的电脑上运行,因此使用连接本地的指令即可。

运行offboard_node

rosrun offboard_pkg offboard_node

最终的效果应该如下图所示,gazebo中的无人机起飞并且悬停在了空中。


文章作者: Immortalqx
版权声明: 本博客所有文章除特別声明外,均采用 CC BY 4.0 许可协议。转载请注明来源 Immortalqx !
评论
  目录