This project presents control of a PX4 - IRIS Quad-copter in Gazebo Simulation using ROS.
AÂ control script written in python requires the input of x, y & z coordinates as drone's goal position and commands the drone to fly towards the location.
Launch Empty Gazebo World
A launch file starts gazebo simulation software with an empty world and an asphalt plane model along with sun and ground as basic components.
roslaunch offboard_py empty_world.launch
<launch>
<!-- gazebo configs -->
<arg name="gui" default="true"/>
<arg name="debug" default="false"/>
<arg name="verbose" default="false"/>
<arg name="paused" default="false"/>
<arg name="respawn_gazebo" default="false"/>
<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
<!-- Gazebo sim -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="gui" value="$(arg gui)"/>
<arg name="world_name" value="$(arg world)"/>
<arg name="debug" value="$(arg debug)"/>
<arg name="verbose" value="$(arg verbose)"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
</include>
</launch>
Spawn IRIS Quad-copter Model in Gazebo
This launch spawns a quad-copter model in a running gazebo simulation. The model is exported from a collection of xacro and STL files.
roslaunch offboard_py spawn_model.launch
<launch>
<!-- Posix SITL environment launch script -->
<!-- launches PX4 SITL and spawns vehicle -->
<!-- vehicle pose -->
<arg name="x" default="0"/>
<arg name="y" default="0"/>
<arg name="z" default="0"/>
<arg name="R" default="0"/>
<arg name="P" default="0"/>
<arg name="Y" default="0"/>
<!-- vehicle model-->
<arg name="est" default="ekf2"/>
<arg name="vehicle" default="iris"/>
<arg name="sdf" default="$(find mavlink_sitl_gazebo)/models/$(arg vehicle)/$(arg vehicle).sdf"/>
<env name="PX4_SIM_MODEL" value="gazebo-classic_$(arg vehicle)" />
<!-- PX4 configs -->
<arg name="interactive" default="true"/>
<!-- PX4 SITL -->
<arg unless="$(arg interactive)" name="px4_command_arg1" value="-d"/>
<arg if="$(arg interactive)" name="px4_command_arg1" value=""/>
<node name="sitl" pkg="px4" type="px4" output="screen"
args="$(find px4)/build/px4_sitl_default/etc -s etc/init.d-posix/rcS $(arg px4_command_arg1)"
required="true"/>
<!-- gazebo model -->
<node name="$(anon vehicle_spawn)" pkg="gazebo_ros" type="spawn_model" output="screen" args="-sdf -file
$(arg sdf) -mode
</launch>
Launch px4.launch from MAVROS pkg
Robot Operating System (ROS) is a general-purpose robotics library that can be used to create powerful drone applications for the PX4 Autopilot.
Using the "original version of ROS" and the MAVROS package to communicate with PX4 over MAVLink (MAVROS bridges ROS topics to MAVLink and PX4 conventions).
MAVROS is a ROS 1 package that enables MAVLink extendable communication between computers running ROS 1 for any MAVLink enabled autopilot, ground station, or peripheral. MAVROS is the "official" supported bridge between ROS 1 and the MAVLink protocol.
roslaunch offboard_py mavros_px4.launch
<launch>
<!-- MAVROS configs -->
<arg name="fcu_url" default="udp://:14540@localhost:14557"/>
<arg name="respawn_mavros" default="false"/>
<!-- MAVROS -->
<include file="$(find mavros)/launch/px4.launch">
<!-- GCS link is provided by SITL -->
<arg name="gcs_url" value=""/>
<arg name="fcu_url" value="$(arg fcu_url)"/>
<arg name="respawn_mavros" value="$(arg respawn_mavros)"/>
</include>
</launch>
Fly Off-board Control Commands Script
OFFBOARD control with MAVROS Python, using an Iris quadcopter simulated in Gazebo Classic.
This Launch file launches a offboard control python script to control the quad-copter, it gives a position goal to the quad-copter and it flys towards the goal, once reached to the goal position it maintaines the position.
roslaunch offboard_py start_offb.launch
<launch>
<!-- Our node to control the drone -->
<node pkg="offboard_py" type="offb_node.py" name="offb_node_py" required="true" output="screen" />
</launch>
Control Script
#!/usr/bin/env python3
import rospy
from geometry_msgs.msg import PoseStamped
# The mavros_msgs package contains all of the custom messages required
# to operate services and topics provided by the MAVROS package
from mavros_msgs.msg import State
from mavros_msgs.srv import CommandBool, CommandBoolRequest, SetMode, SetModeRequest
current_state = State()
# callback which will save the current state of the autopilot
# will allow us to check connection, arming and OFFBOARD flags
def state_cb(msg):
global current_state
current_state = msg
if __name__ == "__main__":
rospy.init_node("offb_node_py")
# instantiate a publisher to publish the commanded local position and the appropriate clients to request
arming and mode
state_sub = rospy.Subscriber("mavros/state", State, callback = state_cb)
local_pos_pub = rospy.Publisher("mavros/setpoint_position/local", PoseStamped, queue_size=10)
rospy.wait_for_service("/mavros/cmd/arming")
arming_client = rospy.ServiceProxy("mavros/cmd/arming", CommandBool)
rospy.wait_for_service("/mavros/set_mode")
set_mode_client = rospy.ServiceProxy("mavros/set_mode", SetMode)
# PX4 has a timeout of 500ms between two OFFBOARD commands. If this
# timeout is exceeded, the commander will fall back to the last mode
# the vehicle was in before entering OFFBOARD mode. This is why the
# publishing rate must be faster than 2 Hz to also account for possible
# latencies.
# Setpoint publishing MUST be faster than 2Hz
rate = rospy.Rate(20)
# Wait for Flight Controller connection
while(not rospy.is_shutdown() and not current_state.connected):
rate.sleep()
pose = PoseStamped()
# Goal Position Setpoint
pose.pose.position.x = 15
pose.pose.position.y = 15
pose.pose.position.z = 2
# Send a few setpoints before starting
for i in range(100):
if(rospy.is_shutdown()):
break
local_pos_pub.publish(pose)
rate.sleep()
offb_set_mode = SetModeRequest()
offb_set_mode.custom_mode = 'OFFBOARD'
arm_cmd = CommandBoolRequest()
arm_cmd.value = True
last_req = rospy.Time.now()
while(not rospy.is_shutdown()):
if(current_state.mode != "OFFBOARD" and (rospy.Time.now() - last_req) > rospy.Duration(5.0)):
if(set_mode_client.call(offb_set_mode).mode_sent == True):
rospy.loginfo("OFFBOARD enabled")
last_req = rospy.Time.now()
else:
if(not current_state.armed and (rospy.Time.now() - last_req) > rospy.Duration(5.0)):
if(arming_client.call(arm_cmd).success == True):
rospy.loginfo("Vehicle armed")
last_req = rospy.Time.now()
local_pos_pub.publish(pose)
rate.sleep()