目錄
一、創(chuàng)建工作空間
1.創(chuàng)建工作空間 catkin_ws
2.編譯工作空間 catkin_make
二、offboard位置控制定點起飛
1.準備工作
2.啟動
三、offboard位置控制y=x2軌跡飛行
一、創(chuàng)建工作空間
參考ROS學習--第3篇:ROS基礎---創(chuàng)建工作空間
1.創(chuàng)建工作空間 catkin_ws
打開終端,創(chuàng)建src文件夾:
mkdir -p ~/catkin_ws/src
進入src文件夾:
cd ~/catkin_ws/src
初始化文件夾:
catkin_init_workspace
2.編譯工作空間 catkin_make
進入catkin_ws文件夾:
cd ~/catkin_ws/
編譯:
catkin_make
二、offboard位置控制定點起飛
參考ROS+PX4學習與開發(fā) 2.0 ROS與PX4的通信、[PX4]mavros安裝+offboard控制過程記錄
1.準備工作
進入catking_ws/src文件夾:
cd ~/catkin_ws/src
創(chuàng)建功能包文件夾:
catkin_create_pkg offboard_pkg roscpp std_msgs geometry_msgs mavros_msgs
進入創(chuàng)建好的功能包文件夾的src文件夾內(nèi):
cd ~/catkin_ws/src/offboard_pkg/src/
新建一個offboard_node.cpp文件:
touch offboard_node.cpp
然后打開.cpp文件進行編輯,這里用gedit:
gedit 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文件夾并編譯
cd ~/catkin_ws/
catkin_make
打開終端設置環(huán)境變量:
echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc
到此前期準備已經(jīng)完畢,可以啟動。
2.啟動
打開1號終端,進入PX4文件夾,打開gazebo:
cd ~/PX4-Autopilot/
make px4_sitl gazebo_iris
啟動QGC,等待QGC連接成功。
打開2號終端,啟動PX4與Mavros之間的連接:
roslaunch mavros px4.launch fcu_url:="udp://:14540@127.0.0.1:14557"
打開3號終端,運行官方示例:
rosrun offboard_pkg offboard_node
稍微等待一會,3號終端如下圖所示,正常情況下能看到gazebo中的無人機升高到2m位置。
?如果啟動之后,3號終端一直跳offboard enabled但是始終不見Vehicle armed,而且gazebo中無人機也沒有反應,可能是PX4版本太新了(13.0),解決辦法是安裝1.12.3。
在主文件夾中刪除PX4-Autopilot整個文件夾,然后打開終端克隆舊版本:
git clone -b v1.12.3 https://github.com/PX4/PX4-Autopilot.git --recursive
如果下載失敗提前結束,報錯:
error: RPC failed; curl 56 GnuTLS recv error (-9): A TLS packet with unexpected length was received.
fatal: The remote end hung up unexpectedly
fatal: early EOF
fatal: index-pack failed
Failed during: git fetch origin --force
首先檢查網(wǎng)絡情況(梯子),網(wǎng)絡檢查過沒問題還是不行,則在終端輸入,然后重新下載:
git config --global http.postBuffer 524288000
git config --global http.maxRequestBuffer 100M
git config --global core.compression 0
export GIT_TRACE_PACKET=1
export GIT_TRACE=1
export GIT_CURL_VERBOSE=1
如果還是解決不了,參考以下帖子:
【Git】error: RPC failed; curl 56 GnuTLS recv error (-9): A TLS packet with unexpected length was rece
下載PX4固件時網(wǎng)絡太慢,經(jīng)常出現(xiàn)克隆失敗
解決git clone 完成后提示'error: RPC failed; curl 56 GnuTLS recv error (-9)'
RPC failed; curl 56 GnuTLS recv error (-54): Error in the pull function.
下載成功之后,編譯。
cd PX4-Autopilot
sudo bash ./Tools/setup/ubuntu.sh
make px4_sitl_default gazebo
如果途中出現(xiàn)問題,參考PX4從放棄到精通(二):ubuntu18.04配置px4編譯環(huán)境及mavros環(huán)境
重新在.bashrc中添加一下px4源碼的路徑:
gedit .bashrc
打開后應該可以找到以前添加過得這一段:
source ~/PX4-Autopilot/Tools/setup_gazebo.bash ~/PX4-Autopilot/ ~/PX4-Autopilot/build/px4_sitl_default
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:~/PX4-Autopilot
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:~/PX4-Autopilot/Tools/sitl_gazebo
將其剪切到.bashrc的最下方,保存關閉,然后終端進行刷新
source .bashrc
之后問題解決,重新上面的啟動步驟。
如果出現(xiàn)了屏幕突然旋轉的情況,解決辦法:
xrandr --output eDP-1 --rotate normal
其中eDP-1是顯示屏名字,替換為自己的顯示屏名字。
三、offboard位置控制y=x2軌跡飛行
參考ROS+PX4無人機室內(nèi)多點飛行代碼文章來源:http://www.zghlxwxcb.cn/news/detail-743644.html
對其.cpp文件修改。文章來源地址http://www.zghlxwxcb.cn/news/detail-743644.html
/**
* @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>
#include <nav_msgs/Odometry.h>//里程計信息格式
int flag = 1;
mavros_msgs::State current_state;
nav_msgs::Odometry local_pos;
void local_pos_cb(const nav_msgs::Odometry::ConstPtr& msg);
void state_cb(const mavros_msgs::State::ConstPtr& msg);
int main(int argc, char **argv)
{
ros::init(argc, argv, "offboard_multi_position");
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::Subscriber local_pos_sub = nh.subscribe<nav_msgs::Odometry>("/mavros/local_position/odom", 10, local_pos_cb);
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 = 3;
//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();
//此處滿足一次請求進入offboard模式即可,官方例成循環(huán)切入offboard會導致無人機無法使用遙控器控制
while(ros::ok())
{
//請求進入OFFBOARD模式
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();
}
}
if(ros::Time::now() - last_request > ros::Duration(5.0))
{
break;
}
local_pos_pub.publish(pose);
ros::spinOnce();
rate.sleep();
}
while(ros::ok())
{
if((flag == 1) && (ros::Time::now() - last_request > ros::Duration(5.0)))
{
ROS_INFO("Position_1");
pose.pose.position.x = 0;
pose.pose.position.y = 0;
pose.pose.position.z = 3;
last_request = ros::Time::now();
flag=2;
}
if((flag ==2) && (ros::Time::now() - last_request > ros::Duration(5.5)))
{
ROS_INFO("Position_2 ");
pose.pose.position.x = pose.pose.position.x + 0.5;
pose.pose.position.y = (pose.pose.position.x)*(pose.pose.position.x);
pose.pose.position.z = 3;
last_request = ros::Time::now();
flag=3;
}
if((flag ==3) && (ros::Time::now() - last_request > ros::Duration(0.5)))
{
ROS_INFO("Position_3 ");
pose.pose.position.x = pose.pose.position.x + 0.5;
pose.pose.position.y = (pose.pose.position.x)*(pose.pose.position.x);
pose.pose.position.z = 3;
last_request = ros::Time::now();
flag=4;
}
if((flag ==4) && (ros::Time::now() - last_request > ros::Duration(0.5)))
{
ROS_INFO("Position_4 ");
pose.pose.position.x = pose.pose.position.x + 0.5;
pose.pose.position.y = (pose.pose.position.x)*(pose.pose.position.x);
pose.pose.position.z = 3;
last_request = ros::Time::now();
flag=5;
}
if((flag ==5) && (ros::Time::now() - last_request > ros::Duration(0.5)))
{
ROS_INFO("Position_5 ");
pose.pose.position.x = pose.pose.position.x + 0.5;
pose.pose.position.y = (pose.pose.position.x)*(pose.pose.position.x);
pose.pose.position.z = 3;
last_request = ros::Time::now();
flag=6;
}
if((flag ==6) && (ros::Time::now() - last_request > ros::Duration(0.5)))
{
ROS_INFO("Position_6 ");
pose.pose.position.x = pose.pose.position.x + 0.5;
pose.pose.position.y = (pose.pose.position.x)*(pose.pose.position.x);
pose.pose.position.z = 3;
last_request = ros::Time::now();
flag=7;
}
if((flag ==7) && (ros::Time::now() - last_request > ros::Duration(0.5)))
{
ROS_INFO("Position_7 ");
pose.pose.position.x = pose.pose.position.x + 0.5;
pose.pose.position.y = (pose.pose.position.x)*(pose.pose.position.x);
pose.pose.position.z = 3;
last_request = ros::Time::now();
flag=8;
}
if((flag ==8) && (ros::Time::now() - last_request > ros::Duration(0.5)))
{
ROS_INFO("Position_8 ");
pose.pose.position.x = pose.pose.position.x + 0.5;
pose.pose.position.y = (pose.pose.position.x)*(pose.pose.position.x);
pose.pose.position.z = 3;
last_request = ros::Time::now();
flag=9;
}
if((flag ==9) && (ros::Time::now() - last_request > ros::Duration(0.5)))
{
ROS_INFO("Position_9 ");
pose.pose.position.x = pose.pose.position.x + 0.5;
pose.pose.position.y = (pose.pose.position.x)*(pose.pose.position.x);
pose.pose.position.z = 3;
last_request = ros::Time::now();
flag=10;
}
if((flag ==10) && (ros::Time::now() - last_request > ros::Duration(0.5)))
{
ROS_INFO("Position_10 ");
pose.pose.position.x = pose.pose.position.x + 0.5;
pose.pose.position.y = (pose.pose.position.x)*(pose.pose.position.x);
pose.pose.position.z = 3;
last_request = ros::Time::now();
flag=11;
}
if((flag ==11) && (ros::Time::now() - last_request > ros::Duration(0.5)))
{
ROS_INFO("Position_11 ");
pose.pose.position.x = pose.pose.position.x + 0.5;
pose.pose.position.y = (pose.pose.position.x)*(pose.pose.position.x);
pose.pose.position.z = 3;
last_request = ros::Time::now();
flag=12;
}
if((flag ==12) && (ros::Time::now() - last_request > ros::Duration(0.5)))
{
ROS_INFO("Position_12 ");
pose.pose.position.x = pose.pose.position.x + 0.5;
pose.pose.position.y = (pose.pose.position.x)*(pose.pose.position.x);
pose.pose.position.z = 3;
last_request = ros::Time::now();
flag=13;
}
if((flag ==13) && (ros::Time::now() - last_request > ros::Duration(0.5)))
{
ROS_INFO("Position_13 ");
pose.pose.position.x = pose.pose.position.x + 0.5;
pose.pose.position.y = (pose.pose.position.x)*(pose.pose.position.x);
pose.pose.position.z = 3;
last_request = ros::Time::now();
flag=14;
}
if((flag ==14) && (ros::Time::now() - last_request > ros::Duration(8.0)))
{
break;
}
local_pos_pub.publish(pose);
ros::spinOnce();
rate.sleep();
}
ROS_INFO("AUTO.LAND");
offb_set_mode.request.custom_mode = "AUTO.LAND";
set_mode_client.call(offb_set_mode);
return 0;
}
void state_cb(const mavros_msgs::State::ConstPtr& msg)
{
current_state = *msg;
}
void local_pos_cb(const nav_msgs::Odometry::ConstPtr& msg)
{
local_pos = *msg;
}
到了這里,關于px4+gazebo無人機仿真,定點起飛,y=x2軌跡飛行的文章就介紹完了。如果您還想了解更多內(nèi)容,請在右上角搜索TOY模板網(wǎng)以前的文章或繼續(xù)瀏覽下面的相關文章,希望大家以后多多支持TOY模板網(wǎng)!