Skip to content

Latest commit

 

History

History
329 lines (222 loc) · 11.3 KB

simple_offboard.md

File metadata and controls

329 lines (222 loc) · 11.3 KB

Simple OFFBOARD

Note The following applies to image versions 0.15 and up. Older documentation is still avaliable for version 0.14 (Russian only).

Hint We recommend using our special PX4 firmware for Clever for autonomous flights.

The simple_offboard module of the clever package is intended for simplified programming of the autonomous drone flight (OFFBOARD flight mode). It allows setting the desired flight tasks, and automatically transforms coordinates between frames.

simple_offboard is a high level system for interacting with the flight controller. For a more low level system, see mavros.

Main services are get_telemetry (receive telemetry data), navigate (fly to a given point along a straight line), navigate_global (fly to a point specified as latitude and longitude along a straight line), land (switch to landing mode).

Python samples

You need to create proxies for services before calling them. Use the following template for your programs:

import rospy
from clever import srv
from std_srvs.srv import Trigger

rospy.init_node('flight') # 'flight' is name of your ROS node

get_telemetry = rospy.ServiceProxy('get_telemetry', srv.GetTelemetry)
navigate = rospy.ServiceProxy('navigate', srv.Navigate)
navigate_global = rospy.ServiceProxy('navigate_global', srv.NavigateGlobal)
set_position = rospy.ServiceProxy('set_position', srv.SetPosition)
set_velocity = rospy.ServiceProxy('set_velocity', srv.SetVelocity)
set_attitude = rospy.ServiceProxy('set_attitude', srv.SetAttitude)
set_rates = rospy.ServiceProxy('set_rates', srv.SetRates)
land = rospy.ServiceProxy('land', Trigger)

Unused proxy functions may be removed from the code.

API description

Note Omitted numeric parameters are set to 0.

get_telemetry

Obtains complete telemetry of the drone.

Parameters:

  • frame_idframe for values x, y, z, vx, vy, vz. Example: map, body, aruco_map. Default value: map.

Response format:

  • frame_id — frame;
  • connected – whether there is a connection to FCU;
  • armed - drone arming state (armed if true);
  • mode – current flight mode;
  • x, y, z — local position of the drone (m);
  • lat, lon – drone latitude and longitude (degrees), requires GPS module;
  • alt – altitude in the global coordinate system (according to WGS-84 standard, not AMSL!), requires GPS module;
  • vx, vy, vz – drone velocity (m/s);
  • pitch – pitch angle (radians);
  • roll – roll angle (radians);
  • yaw — yaw angle (radians);
  • pitch_rate — angular pitch velocity (rad/s);
  • roll_rate – angular roll velocity (rad/s);
  • yaw_rate – angular yaw velocity (rad/s);
  • voltage – total battery voltage (V);
  • cell_voltage – battery cell voltage (V).

Note Fields that are unavailable for any reason will contain the NaN value.

Displaying drone coordinates x, y and z in the local system of coordinates:

telemetry = get_telemetry()
print telemetry.x, telemetry.y, telemetry.z

Displaying drone altitude relative to the ArUco map:

telemetry = get_telemetry(frame_id='aruco_map')
print telemetry.z

Checking global position availability:

import math
if not math.isnan(get_telemetry().lat):
    print 'Global position is available'
else:
    print 'No global position'

Output of current telemetry (command line):

rosservice call /get_telemetry "{frame_id: ''}"

navigate

Fly to the designated point in a straight line.

Parameters:

  • x, y — coordinates (m);
  • yaw — yaw angle (radians);
  • yaw_rate – angular yaw velocity (will be used if yaw is set to NaN) (rad/s);
  • speed – flight speed (setpoint speed) (m/s);
  • auto_arm – switch the drone to OFFBOARD mode and arm automatically (the drone will take off);
  • frame_idcoordinate system for values x, y, z, vx, vy, vz. Example: map, body, aruco_map. Default value: map.

Note If you don't want to change your current yaw set the yaw parameter to NaN (angular velocity by default is 0).

Ascending to the altitude of 1.5 m with the climb rate of 0.5 m/s:

navigate(x=0, y=0, z=1.5, speed=0.5, frame_id='body', auto_arm=True)

Flying in a straight line to point 5:0 (altitude 2) in the local system of coordinates at the speed of 0.8 m/s (yaw is set to 0):

navigate(x=5, y=0, z=3, speed=0.8)

Flying to point 5:0 without changing the yaw angle (yaw = NaN, yaw_rate = 0):

navigate(x=5, y=0, z=3, speed=0.8, yaw=float('nan'))

Flying 3 m to the right from the drone:

navigate(x=0, y=-3, z=0, speed=1, frame_id='body')

Flying 2 m to the left from the last navigation target:

navigate(x=0, y=2, z=0, speed=1, frame_id='navigate_target')

Turn 90 degrees counterclockwise:

navigate(yaw=math.radians(-90), frame_id='body')

Flying to point 3:2 (with the altitude of 2 m) in the ArUco map coordinate system with the speed of 1 m/s:

navigate(x=3, y=2, z=2, speed=1, frame_id='aruco_map')

Rotating on the spot at the speed of 0.5 rad/s (counterclockwise):

navigate(x=0, y=0, z=0, yaw=float('nan'), yaw_rate=0.5, frame_id='body')

Flying 3 meters forwards at the speed of 0.5 m/s, yaw-rotating at the speed of 0.2 rad/s:

navigate(x=3, y=0, z=0, speed=0.5, yaw=float('nan'), yaw_rate=0.2, frame_id='body')

Ascending to the altitude of 2 m (command line):

rosservice call /navigate "{x: 0.0, y: 0.0, z: 2, yaw: 0.0, yaw_rate: 0.0, speed: 0.5, frame_id: 'body', auto_arm: true}"

Note Consider using the navigate_target frame instead of body for missions that primarily use relative movements forward/back/left/right. This negates inaccuracies in relative point calculations.

navigate_global

Flying in a straight line to a point in the global coordinate system (latitude/longitude).

Parameters:

  • lat, lon — latitude and longitude (degrees);
  • z — altitude (m);
  • yaw — yaw angle (radians);
  • yaw_rate – angular yaw velocity (used for setting the yaw to NaN) (rad/s);
  • speed – flight speed (setpoint speed) (m/s);
  • auto_arm – switch the drone to OFFBOARD and arm automatically (the drone will take off);
  • frame_idcoordinate system for z and yaw (Default value: map).

Note If you don't want to change your current yaw set the yaw parameter to NaN (angular velocity by default is 0).

Flying to a global point at the speed of 5 m/s, while maintaining current altitude (yaw will be set to 0, the drone will face East):

navigate_global(lat=55.707033, lon=37.725010, z=0, speed=5, frame_id='body')

Flying to a global point without changing the yaw angle (yaw = NaN, yaw_rate = 0):

navigate_global(lat=55.707033, lon=37.725010, z=0, speed=5, yaw=float('nan'), frame_id='body')

Flying to a global point (command line):

rosservice call /navigate_global "{lat: 55.707033, lon: 37.725010, z: 0.0, yaw: 0.0, yaw_rate: 0.0, speed: 5.0, frame_id: 'body', auto_arm: false}"

set_position

Set the setpoint for position and yaw. This service may be used to specify the continuous flow of target points, for example, for flying along complex trajectories (circular, arcuate, etc.).

Hint Use the navigate higher-level service to fly to a point in a straight line or to perform takeoff.

Parameters:

  • x, y, z — point coordinates (m);
  • yaw — yaw angle (radians);
  • yaw_rate – angular yaw velocity (used for setting the yaw to NaN) (rad/s);
  • auto_arm – switch the drone to OFFBOARD and arm automatically (the drone will take off);
  • frame_idcoordinate system for x, y, z and yaw parameters (Default value: map).

Hovering on the spot:

set_position(frame_id='body')

Assigning the target point 3 m above the current position:

set_position(x=0, y=0, z=3, frame_id='body')

Assigning the target point 1 m ahead of the current position:

set_position(x=1, y=0, z=0, frame_id='body')

Rotating on the spot at the speed of 0.5 rad/s:

set_position(x=0, y=0, z=0, frame_id='body', yaw=float('nan'), yaw_rate=0.5)

set_velocity

Set speed and yaw setpoints.

  • vx, vy, vz – flight speed (m/s);
  • yaw — yaw angle (radians);
  • yaw_rate – angular yaw velocity (used for setting the yaw to NaN) (rad/s);
  • auto_arm – switch the drone to OFFBOARD and arm automatically (the drone will take off);
  • frame_idcoordinate system for vx, vy, vz and yaw (Default value: map).

Note Parameter frame_id specifies only the orientation of the resulting velocity vector, but not its length.

Flying forward (relative to the drone) at the speed of 1 m/s:

set_velocity(vx=1, vy=0.0, vz=0, frame_id='body')

One possible way of flying in a circle:

set_velocity(vx=0.4, vy=0.0, vz=0, yaw=float('nan'), yaw_rate=0.4, frame_id='body')

set_attitude

Set pitch, roll, yaw and throttle level (similar to the STABILIZED mode). This service may be used for lower level control of the drone behavior, or controlling the drone when no reliable data on its position is available.

Parameters:

  • pitch, roll, yaw – requested pitch, roll, and yaw angle (radians);
  • thrust — throttle level, ranges from 0 (no throttle, propellers are stopped) to 1 (full throttle).
  • auto_arm – switch the drone to OFFBOARD mode and arm automatically (the drone will take off);
  • frame_idcoordinate system for yaw (Default value: map).

set_rates

Set pitch, roll, and yaw rates and the throttle level (similar to the ACRO mode). This is the lowest drone control level (excluding direct control of motor rotation speed). This service may be used to automatically perform aerobatic tricks (e.g., flips).

Parameters:

  • pitch_rate, roll_rate, yaw_rate – pitch, roll, and yaw rates (rad/s);
  • thrust — throttle level, ranges from 0 (no throttle, propellers are stopped) to 1 (full throttle).
  • auto_arm – switch the drone to OFFBOARD and arm automatically (the drone will take off);

land

Switch the drone to landing mode (AUTO.LAND or similar).

Note Set the COM_DISARM_LAND PX4 parameter to a value greater than 0 to enable automatic disarm after landing.

Landing the drone:

res = land()

if res.success:
    print 'drone is landing'

Landing the drone (command line):

rosservice call /land "{}"

Additional materials