首先,在目录中建立工作区,并进行初始化操作
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws
catkin init
wstool init src
rosinstall_generator --rosdistro kinetic mavlink | tee /tmp/mavros.rosinstall
rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall
wstool merge -t src /tmp/mavros.rosinstall
wstool update -t src
rosdep install --from-paths src --ignore-src -y
wget https://raw.githubusercontent.com/mavlink/mavros/master/mavros/scripts/install_geographiclib_datasets.sh
sudo chmod 777 install_geographiclib_datasets.sh
sudo ./install_geographiclib_datasets.sh
catkin build
source ~/catkin_ws/devel/setup.bash
然后,在catkin_ws/src目录中运行如下指令
catkin_create_pkg offboard_pkg roscpp std_msgs geometry_msgs mavros_msgs
在~/catkin_ws/src/offboard_pkg/src/目录中新建一个文件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>
int count;
int flag=1;
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, "offboard");
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(8.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();
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();
}
}
if((flag == 1) && (ros::Time::now() - last_request > ros::Duration(5.0)))
{
ROS_INFO("position1(0 , 0, 5)");
pose.pose.position.x = 0;
pose.pose.position.y = 0;
pose.pose.position.z = 5;
last_request = ros::Time::now();
flag=2;
}
if((flag ==2) && (ros::Time::now() - last_request > ros::Duration(5.0)))
{
ROS_INFO("position2(5 , 0, 5)");
pose.pose.position.x = 5.0;
pose.pose.position.y = 0.0;
pose.pose.position.z = 5;
last_request = ros::Time::now();
flag=3;
}
if((flag ==3) && (ros::Time::now() - last_request > ros::Duration(5.0)))
{
ROS_INFO("position3(5 , 5, 5)");
pose.pose.position.x = 5.0;
pose.pose.position.y = 5.0;
pose.pose.position.z = 5;
last_request = ros::Time::now();
flag=4;
}
if((flag ==4) && (ros::Time::now() - last_request > ros::Duration(5.0)))
{
ROS_INFO("position4(0 , 5, 5)");
pose.pose.position.x = 0;
pose.pose.position.y = 5.0;
pose.pose.position.z = 5;
last_request = ros::Time::now();
flag=5;
}
if((flag ==5) && (ros::Time::now() - last_request > ros::Duration(5.0)))
{
ROS_INFO("position5(0 ,0, 5)");
pose.pose.position.x = 0;
pose.pose.position.y = 0;
pose.pose.position.z = 5;
last_request = ros::Time::now();
flag=1;
}
local_pos_pub.publish(pose);
ros::spinOnce();
rate.sleep();
}
return 0;
}
该代码的作用为让无人机飞至5米高度,然后循环按照正方形轨迹飞行
然后打开目录~/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 build
然后,使终端进入PX4的安装目录下,运行命令
make px4_sitl gazebo_iris
即可进入gazebo仿真界面
接着,打开QGC地面站,并运行如下命令连接Mavros和PX4
roslaunch mavros px4.launch fcu_url:="udp://:14540@127.0.0.1:14557"
执行刚才的C++文件
source ~/catkin_ws/devel/setup.bash
rosrun offboard_pkg offboard_node
在gazebo中观察仿真结果即可。
本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)