Skip to content

Latest commit

 

History

History
254 lines (153 loc) · 6.02 KB

py_gnc_functions.md

File metadata and controls

254 lines (153 loc) · 6.02 KB

iq

The python version of the API has been designed to work as seamlessly and easily as the c++ version of the API. But since the python version has been implemented with classes the user should create an object for the API.

The init_publisher_subscriber() has been removed in the python version and will be initialized when the object of the class is created.

Hey there is a C++ version of the API whose documentation is here.

Example Programs

How to run example programs:

$ rosrun iq_gnc <example_program.py>

Note
You have to make the python files executable. You can do this by:

$ cd ~/catkin_ws/src/iq_gnc/scripts/
$ chmod +x *.py 
    • Example program that will make the drone move in a square.
    • Example program showing how to use a ROS subscriber to take input into your drone's guidance node.
    • Simple search and rescue program that will fly a search pattern until YOLO detects a person. This will trigger the drone to land to deliver the rescue supplies.
    • Example obstacle avoidance program utilizing the potential field method to avoid obstacles.

API Explanation

How to call/use the API:

	from iq_gnc.py_gnc_functions import *

	drone = gnc_api()

get_current_heading

 | get_current_heading()

Returns the current heading of the drone.

Returns:

  • Heading Float - θ in is degrees.

get_current_location

 | get_current_location()

Returns the current position of the drone.

Returns:

  • Position geometry_msgs.msgs.Point() - Returns position of type Point().

land

 | land()

The function changes the mode of the drone to LAND.

Returns:

  • 0 int - LAND successful.
  • -1 int - LAND unsuccessful.

wait4connect

 | wait4connect()

Wait for connect is a function that will hold the program until communication with the FCU is established.

Returns:

  • 0 int - Connected to FCU.
  • -1 int - Failed to connect to FCU.

wait4start

 | wait4start()

This function will hold the program until the user signals the FCU to mode enter GUIDED mode. This is typically done from a switch on the safety pilot's remote or from the Ground Control Station.

Returns:

  • 0 int - Mission started successfully.
  • -1 int - Failed to start mission.

set_mode

 | set_mode(mode)

This function changes the mode of the drone to a user specified mode. This takes the mode as a string.
Ex. set_mode("GUIDED").

Arguments:

Returns:

  • 0 int - Mode Set successful.
  • -1 int - Mode Set unsuccessful.

set_speed

 | set_speed(speed_mps)

This function is used to change the speed of the vehicle in guided mode. It takes the speed in meters per second as a float as the input.

Arguments:

  • speed_mps Float - Speed in m/s.

Returns:

  • 0 int - Speed set successful.
  • -1 int - Speed set unsuccessful.

set_heading

 | set_heading(heading)

This function is used to specify the drone's heading in the local reference frame. Psi is a counter clockwise rotation following the drone's reference frame defined by the x axis through the right side of the drone with the y axis through the front of the drone.

Arguments:

  • heading Float - θ(degree) Heading angle of the drone.

set_destination

 | set_destination(x, y, z, psi)

This function is used to command the drone to fly to a waypoint. These waypoints should be specified in the local reference frame. This is typically defined from the location the drone is launched. Psi is counter clockwise rotation following the drone's reference frame defined by the x axis through the right side of the drone with the y axis through the front of the drone.

Arguments:

  • x Float - x(m) Distance with respect to your local frame.
  • y Float - y(m) Distance with respect to your local frame.
  • z Float - z(m) Distance with respect to your local frame.
  • psi Float - θ(degree) Heading angle of the drone.

arm

 | arm()

Arms the drone for takeoff.

Returns:

  • 0 int - Arming successful.
  • -1 int - Arming unsuccessful.

takeoff

 | takeoff(takeoff_alt)

The takeoff function will arm the drone and put the drone in a hover above the initial position.

Arguments:

  • takeoff_alt Float - The altitude at which the drone should hover.

Returns:

  • 0 int - Takeoff successful.
  • -1 int - Takeoff unsuccessful.

initialize_local_frame

 | initialize_local_frame()

This function will create a local reference frame based on the starting location of the drone. This is typically done right before takeoff. This reference frame is what all of the the set destination commands will be in reference to.


check_waypoint_reached

 | check_waypoint_reached(pos_tol=0.3, head_tol=0.01)

This function checks if the waypoint is reached within given tolerance and returns an int of 1 or 0. This function can be used to check when to request the next waypoint in the mission.

Arguments:

  • pos_tol float, optional - Position tolerance under which the drone must be with respect to its position in space. Defaults to 0.3.
  • head_tol float, optional - Heading or angle tolerance under which the drone must be with respect to its orientation in space. Defaults to 0.01.

Returns:

  • 1 int - Waypoint reached successfully.
  • 0 int - Failed to reach Waypoint.