pixhawk4飛控作為一款開源且流行的飛控,在其硬體版本上可以支援APM固件與PX4原生固件。本文針對PX4原生固件進行介紹。PX4中的offboard模式能夠接受來自外部的控制指令,搭配機載或支援MAVROS的協同計算機(如tx1,tx2,樹莓派,dji妙算等等),可在PX4飛控平台上加入視覺處理或人工智能,以實作無人機自動控制功能。這裡詳細介紹一個offboard的例程,外部控制飛機自主飛行2m的高度。
首先需要在Ubuntu的環境下安裝好ros,mavros以及px4原生固件
1.為外部控制例程建立一個工作空間
mkdir -p px4_offboard_ws/src
2.建立一個用于offboard的功能包
cd px4_offboard_ws/src
catkin_create_pkg offboard roscpp std_msgs geometry_msgs mavros_msgs
3.建立好ros包過後,建立一個可cpp源檔案用來作為這個功能包的執行檔案
cd offboard/src
gedit offboard_node.cpp
4.offboard_node.cpp中的代碼如下
#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;
}
5.修改CMakeLists.txt為編譯做準備
cd ..
gedit CMakeLists.txt
6.在CMakeLists.txt最末尾添加如下内容後儲存退出
add_executable(${PROJECT_NAME}_node src/offboard_node.cpp)
target_link_libraries(${PROJECT_NAME}_node
${catkin_LIBRARIES}
)
7.開始編譯
cd ~/px4_offboard_ws
catkin_make
8.把這個工作空間添加到.bashrc裡面友善啟動節點
echo "source ~/px4_offboard_ws/devel/setup.bash" >> ~/.bashrc
9.通過jmavsim進行軟體在環仿真,打開一個終端啟動仿真
cd px4_source_code/Firmware
make px4_sitl_default jmavsim
10.再開一個終端運作mavros
roslaunch mavros px4.launch fcu_url:="udp://:[email protected]:14557"
11.打開一個終端運作外部控制的節點
rosrun offboard offboard_node
12.打開qgc地面站,可以觀察此時飛機飛行高度為2m
