Introduction
Welcome to API reference documentation for FlytOS. Here you can find details of all the FlytAPIs with their description, parameters and usage examples. API bindings are available in several languages and you can select the desired language from the tabs in the right panel.
If you are FlytCloud customer, base IP/URL for API is https://dev.flytbase.com
To learn more about how to get started with FlytOS and build your first app, please visit the developer documentation.
In case, you find any bug/issue in this documentation, please help us rectify it by raising an issue in our github repository.
Namespace API
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /get_global_namespace
ROS-Service Type: core_api/ParamGetGlobalNamespace, below is its description
#Request : None
#Response : Paramter info
core_api/ParamInfo param_info
#Response : success=true if parameter get was successful.
bool success
#Response : Returns error message/success message if any.
string message
// global namespace is not required for any CPP API
# global namespace is not required for any Python API
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /get_global_namespace
call srv: NULL
response srv:
:bool success
:core_api/ParamInfo param_info
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /get_global_namespace
response srv: ParamGetGlobalNamespace
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: ' <ip>/ros/get_global_namespace'
JSON Response:
{
success: Boolean,
message: String,
param_info:{
param_value: String
}
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/get_global_namespace',
serviceType: 'core_api/ParamGetGlobalNamespace'
Response:
{ success: Boolean,
message: String,
param_info:{
param_value: String
}
}
Example
rosservice call /get_global_namespace "{}"
// global namespace is not required for any CPP API
# global namespace is not required for any Python API
#include <core_api/ParamGetGlobalNamespace.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::ParamGetGlobalNamespace>("/get_global_namespace");
core_api::ParamGetGlobalNamespace srv;
client.call(srv);
std::string global_namespace = srv.response.param_info.param_value;
bool success = srv.response.success;
std::string message = srv.response.message;
import rospy
from core_api.srv import *
def get_global_namespace():
rospy.wait_for_service('/get_global_namespace')
try:
res = rospy.ServiceProxy('/get_global_namespace', ParamGetGlobalNamespace)
op = res()
return str(op.param_info.param_value)
except rospy.ServiceException, e:
rospy.logerr("global namespace service not available", e)
return None
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/get_global_namespace",
success: function(data){
console.log(data.param_info.param_value);
}
});
var namespace = new ROSLIB.Service({
ros : ros,
name : '/get_global_namespace',
serviceType : 'core_api/ParamGetGlobalNamespace'
});
var request = new ROSLIB.ServiceRequest({});
namespace.callService(request, function(result) {
console.log('Result for service call on '
+ namespace.name
+ ': '
+ result.param_info.param_value);
});
Example response
param_info:
param_id: global_namespace
param_value: flytpod
success: True
message: FlytOS namespace is flytpod
// global namespace is not required for any CPP API
# global namespace is not required for any Python API
success : true
message : FlytOS namespace is flytpod
success: True
message: FlytOS namespace is flytpod
{
success:True,
param_info:{
param_value:'flytpod'
}
}
{
success:True,
param_info:{
param_value:'flytpod'
}
}
Description:
This API returns the global namespace under which FlytOS’s instance is running. For users using RESTful, Websocket or ROS APIs, calling this API is a MUST, as the value of this namespace is required to call other APIs.
In the subsequent documentation, wherever <namespace> is mentioned in API call definition, it must be replaced by the output of this API call.
Users writing their code in simple CPP and Python need not call this API.
API usage information:
- Global namespace is required when calling onboard/remote APIs except cpp/python APIs.
- All the core nodes of FlytOS run inside this namespace.
- Make sure that your custom ROS packages are not launched inside this namespace.
ROS endpoint:
- Service Type:
Ros Service
- Name:
/get_global_namespace
- Service Type:
ParamGetGlobalNamespace
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
http://<ip>/ros/get_global_namespace
- Request Method:
GET
- JSON Response:
{success: Boolean,message: String,param_info:{param_value: String}}
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library. Java websocket clients are supported using rosjava.
- name:
/get_global_namespace
- serviceType:
core_api/ParamGetGlobalNamespace
Navigation APIs
Access Request
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/access_request
ROS-Service Type: core_api/AccessRequest, below is its description
#Request :
bool enable_access
#Response : return success=true if command is successful
bool success
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: int Navigation::access_request(bool enable_access)
Arguments: enable_access: Set it to True to enable API access
Returns: returns 0 if the command is successfully sent to the vehicle
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.api.navigation
Function: access_request(enable_access)
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/access_request
call srv:
:bool enable_access
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/access_request
call srv:
:bool enable_access
response srv:
:bool success
:string message
This is a REST call to enable API control over drone. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/access_request'
JSON Request:
{
enable_access: Boolean
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call to enable API control over drone. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/access_request',
serviceType: 'core_api/AccessRequest'
Request:
{
enable_access: Boolean
}
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytos/navigation/access_request "{enable_access: true}"
#include <cpp_api/navigation_bridge.h>
Navigation nav;
if(!nav.access_request())
cout<<"API access enabled";
else
cout<<"Failed to enable API access";
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
# wait for interface to initialize
time.sleep(3.0)
drone.access_request()
#include <core_api/AccessRequest.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::AccessRequest>("/<namespace>/navigation/access_request");
core_api::AccessRequest srv;
srv.request.enable_access=true;
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
import rospy
from core_api.srv import *
def access_request(enable_access)
rospy.wait_for_service('/<namespace>/navigation/access_request')
try:
handle = rospy.ServiceProxy('/<namespace>/navigation/access_request', AccessRequest)
resp = handle(enable_access=enable_access)
return resp
except rospy.ServiceException, e:
rospy.logerr("service call failed %s", e)
var msgdata={};
msgdata["enable_access"]=true;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/navigation/access_request",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var access_request = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/access_request',
serviceType : 'core_api/AccessRequest'
});
var request = new ROSLIB.ServiceRequest({
enable_access = true
});
access_request.callService(request, function(result) {
console.log('Result for service call on '
+ access_request.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
True
success: True
Success: True
{
success:True
}
{
success:True
}
Description:
This API enables API control over drone. Sending vehicle to GUIDED/OFFBOARD mode via RC automatically enables API control, and likewise sending vehicle to RC modes such as MANUAL/STABILIZE/ALTCTL/ALT_HOLD/POSCTL/POSHOLD/LOITER disables API control.
If this API is called with enable_access argument set to ‘true’, vehicle’s mode is shifted to GUIDED/OFFBOARD mode internally.
Parameters:
Following parameters are applicable for onboard C++ and Python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
enable_access | bool | Set this to true to enable API access. Setting this to false won’t have any effect, this feature would be added later. |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
- access_request API MUST be called if you don’t have any RC hooked with the vehicle.
- It is safer to configure RC to communicate with the drone and send the vehicle to GUIDED/OFFBOARD mode instead of calling access_request command.
- All navigation API’s except ‘disarm’ requires that FlytOS’s access to drone has been enabled. So before calling any setpoint / waypoint APIs, make sure to call this API, or send vehicle to GUIDED/OFFBOARD mode via RC.
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type: Ros Service
- Name: /<namespace>/navigation/access_request
- Service Type: core_api/AccessRequest
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/navigation/access_request
- JSON Request: { enable_access: Boolean }
- JSON Response: { success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library. Java websocket clients are supported using rosjava.
- name: ‘/<namespace>/navigation/access_request’
- serviceType: ‘core_api/AccessRequest’
Arm
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/arm
ROS-Service Type: core_api/Arm, below is its description
#Request : NULL
#Response : return success=true if command is successful
bool success
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: int Navigation::arm(void)
Arguments: None
Returns: returns 0 if the command is successfully sent to the vehicle
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.api.navigation
Function: arm()
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/arm
call srv: NULL
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/arm
call srv: NULL
response srv:
:bool success
:string message
This is a REST call for the API to arm the
FlytOS running device. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/arm'
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API to arm the
FlytOS running device. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/arm',
serviceType: 'core_api/Arm'
Request:
{}
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytos/navigation/arm "{}"
#include <cpp_api/navigation_bridge.h>
Navigation nav;
if(!nav.arm())
cout<<"System ARMED";
else
cout<<"Failed to ARM system";
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
# wait for interface to initialize
time.sleep(3.0)
drone.arm()
#include <core_api/Arm.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::Arm>("/<namespace>/navigation/arm");
core_api::Arm srv;
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
import rospy
from core_api.srv import *
def arm()
rospy.wait_for_service('/<namespace>/navigation/arm')
try:
handle = rospy.ServiceProxy('/<namespace>/navigation/arm', Arm)
resp = handle()
return resp
except rospy.ServiceException, e:
rospy.logerr("service call failed %s", e)
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/navigation/arm",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var arm = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/arm',
serviceType : 'core_api/Arm'
});
var request = new ROSLIB.ServiceRequest({});
arm.callService(request, function(result) {
console.log('Result for service call on '
+ arm.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
True
success: True
Success: True
{
success:True
}
{
success:True
}
Description:
This API arms the motors. If arm fails then check debug messages for arming errors. Likely reasons are uncalibrated sensors, misconfiguration.
Parameters:
Following parameters are applicable for onboard C++ and Python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments: None
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
- ARM API will only work when device is in GUIDED or OFFBOARD or API|POSCTL mode.
- All navigation setpoint API’s except take_off require that drone is armed. So before calling any setpoint / waypoint APIs, drone should be armed.
- It is safer to use take_off command instead of arm command.
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/arm
- Service Type:
core_api/Arm
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
GET http://<ip>/ros/<namespace>/navigation/arm
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library. Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/arm
- serviceType:
core_api/Arm
Disarm
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/disarm
ROS-Service Type: core_api/Disarm, below is its description
#Request : NULL
#Response : return success=true if command is successful
bool success
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: int Navigation::disarm(void)
Arguments: None
Returns: returns 0 if the command is successfully sent to the vehicle
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.api.navigation
Function: disarm():
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/disarm
call srv: NULL
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/disarm
call srv: NULL
response srv:
:bool success
:string message
This is a REST call for the API to disarm the
FlytOS running device. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/disarm'
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API to disarm the
FlytOS running device. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/disarm',
serviceType: 'core_api/Disarm'
Request:
{}
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytos/navigation/disarm "{}"
#include <cpp_api/navigation_bridge.h>
Navigation nav;
if(!nav.disarm())
cout<<"System DIARMED";
else
cout<<"Failed to DISARM system";
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
# wait for interface to initialize
time.sleep(3.0)
drone.disarm()
#include <core_api/Disarm.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::Disarm>("/<namespace>/navigation/disarm");
core_api::Disarm srv;
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
import rospy
from core_api.srv import *
def disarm():
rospy.wait_for_service('/<namespace>/navigation/disarm')
try:
handle = rospy.ServiceProxy('/<namespace>/navigation/disarm', Disarm)
resp = handle()
return resp
except rospy.ServiceException, e:
rospy.logerr("service call failed %s", e)
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/navigation/disarm",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var disarm = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/disarm',
serviceType : 'core_api/Disarm'
});
var request = new ROSLIB.ServiceRequest({});
disarm.callService(request, function(result) {
console.log('Result for service call on '
+ disarm.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
True
success: True
Success: True
{
success:True
}
{
success:True
}
Description:
This API disarms the motors. Read API description below before you use it.
Parameters:
Following parameters are applicable for onboard C++ and Python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments: None
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
- This API will work regardless of what flight mode vehicle is in.
- Make sure that drone is on ground before disarming. If this API is called during flight, motors will stop instantly causing the drone to crash.
- To confirm whether vehicle is grounded / landed subscribe to following topic. (/global_namespace/mavros/extended_state), parameter name : landed_state, value: 1 –> ground, 2 –> air/flying.
- If land API is used then the vehicle will automatically disarm after some time.
- Land API with auto diarm on landing feature is preferred over calling disarm API specifically.
- To configure auto disarm on landing set following parameters.
- COM_DISARM_LAND:: 0 : disabled, n (integer between 1 to 20 inculsive) : enabled with n seconds timeout before disarming after landed.
- If this feature is enabled motors will disarm automatically even in cases where vehicle was armed but not flown. So for most scenarios value 5 should be fine.
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/disarm
- Service Type:
core_api/Disarm
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
GET http://<ip>/ros/<namespace>/navigation/disarm
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library. Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/disarm
- serviceType:
core_api/Disarm
Take Off
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/takeoff
ROS-Service Type: core_api/TakeOff, below is its description
# Request : expects take off altitude in metres
float32 takeoff_alt
# Response : returns success=true if takeoff altitude is reached
bool success
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: int Navigation::take_off(float takeoff_alt = 5.0)
Arguments:
takeoff_alt: TakeOff Altitude in meters with default value of 5.0
Returns: 0 if the vehicle reaches takeoff_alt before timeout=30sec, else returns 1.
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.api.navigation
Function: take_off(self, takeoff_alt=5.0):
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/takeoff
call srv:
: int takeoff_alt
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/takeoff
Type: core_api/TakeOff
call srv:
: int takeoff_alt
response srv:
:bool success
:string message
This is a REST call for the API to takeoff. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/take_off'
JSON Request:
{
takeoff_alt: Float
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API to takeoff. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/take_off',
serviceType: 'core_api/TakeOff'
Request:
{ takeoff_alt: Float }
Response:
{ success: Boolean,
message: String, }
Example
rosservice call /flytos/navigation/take_off "takeoff_alt: 3.0"
#include <cpp_api/navigation_bridge.h>
Navigation nav;
nav.take_off(3.0);
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
# wait for interface to initialize
time.sleep(3.0)
# takeoff over current location
drone.take_off(6.0)
#include <core_api/TakeOff.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::TakeOff>("/<namespace>/navigation/takeoff");
core_api::TakeOff srv;
srv.request.takeoff_alt = 3.0;
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
import rospy
from core_api.srv import *
def takeoff(height)
rospy.wait_for_service('/<namespace>/navigation/take_off')
try:
handle = rospy.ServiceProxy('/<namespace>/navigation/take_off', TakeOff)
resp = handle(takeoff_alt=height)
return resp
except rospy.ServiceException, e:
rospy.logerr("service call failed %s", e)
var msgdata={};
msgdata["takeoff_alt"]=5.00;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/navigation/take_off",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var takeoff = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/take_off',
serviceType : 'core_api/TakeOff'
});
var request = new ROSLIB.ServiceRequest({
takeoff_alt: 5.00
});
takeoff.callService(request, function(result) {
console.log('Result for service call on '
+ takeoff.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
True
success: True
Success: True
{
success:True
}
{
success:True
}
Description:
Takeoff and reach specified height from current location.
Parameters:
Following parameters are applicable for onboard C++ and Python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
takeoff_alt | float32 | takeoff to given height at current location. (minimum 1.5 meters) |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
Takeoff to specified height from current height at current location.
- takeoff_alt value should be positive.
- Irrespective of current altitude vechile will climb up by takeoff_alt meters from current location.
- Takeoff API will automatically arm the motors.
- Takeoff API will work only in OFFBOARD/GUIDED/API|POSCTL mode.
- Minimum value of takeoff_alt argument is 1.5 meters.
- Takeoff API is always synchronous.
- It is recommended not to send any other navigation commands while takeoff is under way.
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/takeoff
- Service Type:
core_api/TakeOff
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/navigation/take_off
- JSON Request:
{ takeoff_alt: Float }
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library. Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/take_off
- serviceType:
core_api/TakeOff
Land
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/land
ROS-Service Type: core_api/Land, below is its description
#Request : expects async variable to be set/reset
bool async
#Response : return success=true if Land command sent successfully to autopilot
bool success
string message
// CPP API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from cpp.
Function Definition: int Navigation::land(bool async = false)
Arguments:
async: If true, asynchronous mode is set
Returns: 0 if the land command is successfully sent to the vehicle, else returns 1.
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.api.navigation
Function: land(async=False):
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/land
call srv:
async=false
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/land
call srv:
async=False
response srv:
:bool success
:string message
This is a REST call for the API to land. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/land'
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API to land. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/land',
serviceType: 'core_api/Land'
Request:
{ }
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytos/navigation/land "async=true"
#include <cpp_api/navigation_bridge.h>
Navigation nav;
nav.land(true);
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
# wait for interface to initialize
time.sleep(3.0)
# land at current location. Return after landed
drone.land(async=False)
# land at current location. Function returns immediately and land action finishes asynchronously.
drone.land(async=True)
#include <core_api/Land.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::Land>("/<namespace>/navigation/land");
core_api::Land srv;
srv.request.async = true;
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
import rospy
from core_api.srv import *
def land(async= False):
rospy.wait_for_service('/<namespace>/navigation/land')
try:
handle = rospy.ServiceProxy('/<namespace>/navigation/land', Land)
resp = handle(async)
return resp
except rospy.ServiceException, e:
rospy.logerr("service call failed %s", e)
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/navigation/land",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var land = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/land',
serviceType : 'core_api/Land'
});
var request = new ROSLIB.ServiceRequest({});
land.callService(request, function(result) {
console.log('Result for service call on '
+ land.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
True
success: True
Success: True
{
success:True
}
{
success:True
}
Description:
Land vehicle at current position. Check API usage section below before using this API.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
async | bool | If true, asynchronous mode is set |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
This API will land the vehicle at current location.
- This API can be used only in GUIDED or OFFBOARD or API|POSCTL mode.
- If any other navigation API is called during landing, then land call be overridden by that API call.
- Automatic land flow can be configured with following parameters.
- LNDMC_Z_VEL_MAX : Maximum velocity in vertical direction when landing (ideal value 0.8 m/s to 1.5 m/s)
- LNDMC_XY_VEL_MAX: Maximum velocity in horizontal direction when landing (ideal value 1 m/s to 2 m/s)
- MPC_LAND_SPEED: Landing velocity (ideal value 0.8 m/s)
- To disarm vehicle automatically after landing following parameter can be configured.
- COM_DISARM_LAND:: 0 : disabled, n (integer between 1 to 20 inclusive) : enabled with n seconds timeout before disarming after landed.
- If this feature is enabled motors will disarm automatically even in cases where vehicle was armed but not flown. So for most scenarios value 5 should be fine.
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/land
- Service Type:
core_api/Land
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
GET http://<ip>/ros/<namespace>/navigation/land
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/land
- serviceType:
core_api/Land
Position Hold
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/position_hold
ROS-Service Type: core_api/PositionHold, below is its description
#Request : NULL
#Response : return success=true if command sent successfully to autopilot
bool success
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: int Navigation::position_hold()
Arguments: None
Returns: returns 0 if the command is successfully sent to the vehicle
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.api.navigation
Function: position_hold():
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/position_hold
call srv: NULL
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/position_hold
call srv: NULL
response srv:
:bool success
:string message
This is a REST call for the API to halt and hover at
current location. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/position_hold'
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API to halt and
hover at current location. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/position_hold',
serviceType: 'core_api/PositionHold'
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /<namespace>/navigation/position_hold "{}"
#include <cpp_api/navigation_bridge.h>
Navigation nav;
nav.position_hold();
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
# wait for interface to initialize
time.sleep(3.0)
# hold position
drone.position_hold()
#include <core_api/PositionHold.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::PositionHold>("/<namespace>/navigation/position_hold");
core_api::PositionHold srv;
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
import rospy
from core_api.srv import *
def position_hold():
rospy.wait_for_service('/<namespace>/navigation/position_hold')
try:
handle = rospy.ServiceProxy('/<namespace>/navigation/position_hold', PositionHold)
resp = handle()
return resp
except rospy.ServiceException, e:
rospy.logerr("service call failed %s", e)
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/navigation/position_hold",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var positionHold = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/position_hold',
serviceType : 'core_api/PositionHold'
});
var request = new ROSLIB.ServiceRequest({});
positionHold.callService(request, function(result) {
console.log('Result for service call on '
+ positionHold.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
True
success: True
Success: True
{
success:True
}
{
success:True
}
Description:
Position hold / hover / loiter at current position.
Parameters:
Following parameters are applicable for onboard C++ and Python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments: None
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
This API can be used to stop the vehicle at current location.
- This API requires vehicle to be in GUIDED or OFFBOARD or API|POSCTL mode.
- This API will override current mission / navigation commmands.
- This API requires position lock. GPS, Optical Flow, VICON system can provide position data to vehicle.
- Vehicle may take few seconds to come to rest depending on current linear velocity.
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/position_hold
- Service Type:
core_api/PositionHold
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
GET http://<ip>/ros/<namespace>/navigation/position_hold
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/position_hold
- serviceType:
core_api/PositionHold
Position Setpoint
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/position_set
ROS-Service Type: core_api/PositionSet, below is its description
#Request : expects position setpoint via x, y, z
#Request : expects yaw setpoint via yaw (send yaw_valid=true)
geometry_msgs/TwistStamped twist #deprecated, instead use x,y,z,yaw
float32 x
float32 y
float32 z
float32 yaw
float32 tolerance
bool async
bool relative
bool yaw_valid
bool body_frame
#Response : success=true - (if async=false && if setpoint reached before timeout = 30sec) || (if async=true)
bool success
string message
// CPP API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from cpp.
Function Definition: int Navigation::position_set(float x, float y, float z, float yaw=0, float tolerance=0, bool relative=false, bool async=false, bool yaw_valid=false, bool body_frame=false)
Arguments:
x,y,z: Position Setpoint in NED-Frame (in body-frame if body_frame=true)
yaw: Yaw Setpoint in radians
yaw_valid: Must be set to true, if yaw setpoint is provided
tolerance: Acceptance radius in meters, default value=1.0m
relative: If true, position setpoints relative to current position is sent
async: If true, asynchronous mode is set
body_frame: If true, position setpoints are relative with respect to body frame
Returns: For async=true, returns 0 if the command is successfully sent to the vehicle, else returns 1. For async=false, returns 0 if the vehicle reaches given setpoint before timeout=30secs, else returns 1.
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.api.navigation
Function: position_set(self, x, y, z, yaw=0.0, tolerance=0.0, relative=False, async=False, yaw_valid=False,
body_frame=False):
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/position_set
call srv:
:float x
:float y
:float z
:float yaw
:float tolerance
:bool async
:bool relative
:bool yaw_valid
:bool body_frame
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/position_set
call srv:
:float x
:float y
:float z
:float yaw
:float tolerance
:bool async
:bool relative
:bool yaw_valid
:bool body_frame
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/position_set'
JSON Request:
{
x: Float,
y: Float,
z: Float,
yaw: Float,
tolerance: Float,
async: Boolean,
relative: Boolean,
yaw_valid : Boolean,
body_frame : Boolean
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/position_set',
serviceType: 'core_api/PositionSet'
Request:
{
x: Float,
y: Float,
z: Float,
yaw: Float,
tolerance: Float,
async: Boolean,
relative: Boolean,
yaw_valid : Boolean,
body_frame : Boolean
}
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytos/navigation/position_set "{x: 1.0, y: 3.5, z: -5.0, yaw: 0.12, tolerance: 0.0, async: false, relative: false, yaw_valid: true, body_frame: false}"
#sends (x,y,z)=(1.0,3.5,-5.0)(m), yaw=0.12rad, relative=false, async=false, yaw_valid=true, body_frame=false
#default value of tolerance=1.0m if left at 0
#include <cpp_api/navigation_bridge.h>
Navigation nav;
nav.position_set(1.0, 3.5, -5.0, 0.12, 2.0, false, false, true, false);
//sends (x,y,z)=(1.0,3.5,-5.0)(m), yaw=0.12rad, tolerance=2.0m, relative=false, async=false, yaw_valid=true, body_frame=false
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
# wait for interface to initialize
time.sleep(3.0)
# command vehicle towards 5 metres SOUTH from current location regardless of heading
drone.position_set(-5, 0, 0, relative=True)
#include <core_api/PositionSet.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::PositionSet>("/<namespace>/navigation/position_set");
core_api::PositionSet srv;
srv.request.x = 1.0;
srv.request.y = 3.5;
srv.request.z = -5.0;
srv.request.yaw = 0.12;
srv.request.tolerance = 5.0;
srv.request.async = false;
srv.request.yaw_valid = true;
srv.request.relative = false;
srv.request.body_frame = false;
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
//sends (x,y,z)=(1.0,3.5,-5.0)(m), yaw=0.12rad, tolerance=5.0m, relative=false, async=false, yaw_valid=true, body_frame=false
import rospy
from core_api.srv import *
def setpoint_local_position(lx, ly, lz, yaw, tolerance = 2.0, async = False, relative= False, yaw_valid= False, body_frame= False):
rospy.wait_for_service('/<namespace>/navigation/position_set')
try:
handle = rospy.ServiceProxy('/<namespace>/navigation/position_set', PositionSet)
# building message structure
req_msg = PositionSetRequest(x=lx, y=ly, z=lz, yaw=yaw, tolerance=tolerance, async=async, relative=relative, yaw_valid=yaw_valid, body_frame=body_frame)
resp = handle(req_msg)
return resp
except rospy.ServiceException, e:
rospy.logerr("pos set service call failed %s", e)
var msgdata={};
msgdata["x"]=2.00;
msgdata["y"]=3.00;
msgdata["z"]=-1.00;
msgdata["yaw"]=1.00;
msgdata["tolerance"]=2.00;
msgdata["async"]=true;
msgdata["relative"]=false;
msgdata["yaw_valid"]=true;
msgdata["body_frame"]=false;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/navigation/position_set",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var positionSet = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/position_set',
serviceType : 'core_api/PositionSet'
});
var request = new ROSLIB.ServiceRequest({
x: 2.00,
y: 3.00,
z: -1.00,
yaw: 1.00,
tolerance: 2.00,
async: true,
relative: false,
yaw_valid : true,
body_frame : false
});
positionSet.callService(request, function(result) {
console.log('Result for service call on '
+ positionSet.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
True
success: True
Success: True
{
success:True
}
{
success:True
}
Description:
This API commands the vehicle to go to a specified location in local frame and hover. Please check API usage section below before using API.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
x, y, z | float | Position Setpoint in NED-Frame (in body-frame if body_frame=true) |
yaw | float | Yaw Setpoint in radians |
yaw_valid | bool | Must be set to true, if yaw |
tolerance | float | Acceptance radius in meters, default value=1.0m |
relative | bool | If true, position setpoints relative to current position is sent |
async | bool | If true, asynchronous mode is set |
body_frame | bool | If true, position setpoints are relative with respect to body frame |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
- Vehicle should be in GUIDED or OFFBOARD or API|POSCTL mode for this API to work.
- Vehicle should be armed for this API to work.
- Do not call this API when vehicle is grounded. Use take_off API first to get the vehicle in air.
- X,Y,Z are position setpoints in 3 linear axes. Yaw is angular rotation around Z axis. Right hand notation is used to find positive yaw direction.
- Effect of parameters:
- Async:
- True: The API call would return as soon as the command has been sent to the autopilot, irrespective of whether the vehicle has reached the given setpoint or not.
- False: The API call would wait for the function to return, which happens when either the position setpoint is reached or timeout=30secs is over.
- Relative:
- True: Linear position setpoints (x,y,z) are calculated from current location. Home location is not relevant. Yaw is calculated from North.
- False: Linear position setpoints (x,y,z) are calculated from home location. Home location is reset every time vehicle arms. Yaw is calculated from North.
- Body_frame
- True: All the setpoints are converted to body frame.
- Front of vehicle : +x
- Right of vehicle : +y
- Down: +z
- Yaw is calculated from front of vehicle.
- False: All the setpoints are converted to local NED (North, East, Down) frame. Yaw is calculated from North.
- Async:
- Either body_frame or relative flag can be set to true at a time. If both are set then only body_frame is effective.
- For yaw setpoint to be effective the yaw_valid argument must be set to true.
- This API overrides any previous mission / navigation API being carried out.
- This API requires position lock. GPS, Optical Flow, VICON system can provide position data to vehicle.
- To provide only Yaw setpoint use this API with x,y,z arguments set to 0, relative=True, yaw_valid=True
- Following parameters need to be manually configured according to vehicle frame.
- MPC_XY_VEL_MAX : Maximum horizontal velocity. For smaller and lighter this parameter could be set to value between 8 m/s to 15 m/s. For larger and heavier systems it is safer to set this value below 8 m/s.
- MPC_Z_VEL_MAX : Maximum vertical velocity. For smaller and lighter this parameter could be set to value between 3 m/s to 10 m/s. For larger and heavier systems it is safer to set this value below 8 m/s.
- Vehicle will try to go to the setpoint with maximum velocity. At no point the current velocity will exceed limit set by above parameters. So if you want the vehicle to reach a point slowly then reducen the value of above paramters.
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/position_set
- Service Type:
core_api/PositionSet
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/navigation/position_set
- JSON Request:
{ x: Float, y: Float, z: Float, yaw: Float, tolerance: Float, async: Boolean, relative: Boolean, yaw_valid : Boolean, body_frame : Boolean }
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/position_set
- serviceType:
core_api/PositionSet
Global Position Setpoint
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/position_set_global
ROS-Service Type: core_api/PositionSetGlobal, below is its description
#Request : expects position setpoint via lat_x, long_y, rel_alt_z(altitude from home)
#Request : expects yaw setpoint via yaw (send yaw_valid=true)
geometry_msgs/TwistStamped twist #deprecated, instead use lat_x,long_y,rel_alt_z,yaw
float32 lat_x
float32 long_y
float32 rel_alt_z
float32 yaw
float32 tolerance
bool async
bool yaw_valid
#Response : return success=true, (if async=false && if setpoint reached before timeout = 30sec) || (if async=true && command sent to autopilot)
bool success
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: int position_set_global(float lat_x, float long_y, float rel_alt_z, float yaw=0, float tolerance=0, bool async=false, bool yaw_valid=false);
Arguments:
:lat_x: Latitude
:long_y: Longitude
:rel_alt_z: Altitue (Positive distance upwards from home position)
:yaw: Yaw Setpoint in radians
:yaw_valid: Must be set to true, if yaw setpoint is provided
:tolerance: Acceptance radius in meters, default value=1.0m
:async: If true, asynchronous mode is set
:returns: For async=true, returns 0 if the command is successfully sent to the vehicle, else returns 1. For async=false, returns 0 if the vehicle reaches given setpoint before timeout=30secs, else returns 1.
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.api.navigation
Function: position_set_global(self, lat, lon, rel_ht, yaw=0.0, tolerance=0.0, async=False, yaw_valid=False):
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/position_set_global
call srv:
:float lat_x
:float long_y
:float rel_alt_z
:float yaw
:float tolerance
:bool async
:bool yaw_valid
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/position_set_global
call srv:
:float lat_x
:float long_y
:float rel_alt_z
:float yaw
:float tolerance
:bool async
:bool yaw_valid
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/position_set_global'
JSON Request:
{
lat_x: Float,
long_y: Float,
rel_alt_z: Float,
yaw: Float,
tolerance: Float,
async: Boolean,
relative: Boolean,
yaw_valid : Boolean,
body_frame : Boolean
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/position_set_global',
serviceType: 'core_api/PositionSetGlobal'
Request:
{
lat_x: Float,
long_y: Float,
rel_alt_z: Float,
yaw: Float,
tolerance: Float,
async: Boolean,
relative: Boolean,
yaw_valid : Boolean
}
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytos/navigation/position_set_global "{ lat_x: 8.04303, long_y: 43.57437, rel_alt_z: 5.0, yaw: 0.12 ,tolerance: 0.0, async: false, yaw_valid: true}"
#sends (Lat,Lon,relAlt)=(8.04303, 43.57437,5.0)(m), yaw=0.12rad, async=false, yaw_valid=true
#default value of tolerance=1.0m if left at 0
#include <cpp_api/navigation_bridge.h>
Navigation nav;
nav.position_set_global(10.342124, 13.4323233, 5.0, 0.12, 2.0, false, true);
//sends (Lat,Lon,relAlt)=(10.342124, 13.4323233, 5.0)(m), yaw=0.12rad, tolerance=2.0m, async=false, yaw_valid=true
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
# wait for interface to initialize
time.sleep(3.0)
# send vehicle to GPS coordinate with height 10 meters above home position.
drone.position_set_global(10.342124, 13.4323233, 10)
#include <core_api/PositionSetGlobal.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::PositionSetGlobal>("/<namespace>/navigation/position_set_global");
core_api::PositionSetGlobal srv;
srv.lat_x = 10.342124;
srv.long_y = 13.4323233;
srv.rel_alt_z = 5.0;
srv.yaw = 0.5;
srv.request.tolerance = 2.0;
srv.request.async = true;
srv.request.yaw_valid = true;
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
import rospy
from core_api.srv import *
def setpoint_global_position(lat_x, long_y, rel_alt_z, yaw, tolerance= 0.0, async = False, yaw_valid= False):
rospy.wait_for_service('/<namespace>/navigation/position_set_global')
try:
handle = rospy.ServiceProxy('/<namespace>/navigation/position_set_global', PositionSetGlobal)
# build message structure
req_msg = PositionSetGlobalRequest(lat_x=lat_x, long_y=long_y, rel_alt_z=rel_alt_z, yaw=yaw, tolerance=tolerance, async=async, yaw_valid=yaw_valid)
resp = handle(req_msg)
return resp
except rospy.ServiceException, e:
rospy.logerr("global pos set service call failed %s", e)
var msgdata={};
msgdata["lat_x"]=10.342124;
msgdata["long_y"]=13.4323233;
msgdata["rel_alt_z"]=5.00;
msgdata["yaw"]=1.00;
msgdata["tolerance"]=2.00;
msgdata["async"]=true;
msgdata["relative"]=false;
msgdata["yaw_valid"]=true;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/navigation/position_set_global",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var positionSetGlobal = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/position_set_global',
serviceType : 'core_api/PositionSetGlobal'
});
var request = new ROSLIB.ServiceRequest({
lat_x: 10.342124,
long_y: 13.4323233,
rel_alt_z: 5.00,
yaw: 1.00,
tolerance: 2.00,
async: true,
relative: false,
yaw_valid : true
});
positionSetGlobal.callService(request, function(result) {
console.log('Result for service call on '
+ positionSetGlobal.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
True
success: True
Success: True
{
success:True
}
{
success:True
}
Description:
This API sets a desired position setpoint in global coordinate system (WGS84). Please check API usage section below before using API.
Parameters:
Following parameters are applicable for onboard C++ and Python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
lat_x | float | Latitude |
long_y | float | Longitude |
rel_alt_z | float | relative height from current location in meters |
yaw | float | Yaw Setpoint in radians |
yaw_valid | bool | Must be set to true, if yaw |
tolerance | float | Acceptance radius in meters, default value=1.0m |
async | bool | If true, asynchronous mode is set |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
- Vehicle should be in GUIDED or OFFBOARD or API|POSCTL mode for this API to work.
- Vehicle should be armed for this API to work.
- Do not call this API when vehicle is grounded. Use take_off API first to get the vehicle in air.
- Right hand notation is used to find positive yaw direction.
- rel_alt_z parameter is always positive.
- rel_alt_z parameter should be calculated relative to ground. E.g. If vehicle is at position A hovering above ground at 10 meters and is then commanded to reach to point B which is 5 meters higher than point A then rel_alt_z should be 10+5=15.
- Effect of parameters:
- Async:
- True: The API call would return as soon as the command has been sent to the autopilot, irrespective of whether the vehicle has reached the given setpoint or not.
- False: The API call would wait for the function to return, which happens when either the position setpoint is reached or timeout=30secs is over.
- Async:
- For yaw setpoint to be effective the yaw_valid argument must be set to true.
- This API overrides any previous mission / navigation API being carried out.
- This API requires global position lock. So using a GPS receiver is must for this API to work.
- Following parameters need to be manually configured according to vehicle frame.
- MPC_XY_VEL_MAX : Maximum horizontal velocity. For smaller and lighter this parameter could be set to value between 8 m/s to 15 m/s. For larger and heavier systems it is safer to set this value below 8 m/s.
- MPC_Z_VEL_MAX : Maximum vertical velocity. For smaller and lighter this parameter could be set to value between 3 m/s to 10 m/s. For larger and heavier systems it is safer to set this value below 8 m/s.
- Vehicle will try to go to the setpoint with maximum velocity. At no point the current velocity will exceed limit set by above parameters. So if you want the vehicle to reach a point slowly then reducen the value of above paramters.
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/position_set_global
- Service Type:
PositionSetGlobal
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/navigation/position_set_global
- JSON Request:
{ lat_x: Float, long_y: Float, rel_alt_z: Float, yaw: Float, tolerance: Float, async: Boolean, relative: Boolean, yaw_valid : Boolean }
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library. Java websocket clients are supported using rosjava.
- name: ‘/<namespace>/navigation/position_set_global’
- serviceType: ‘core_api/PositionSetGlobal’
Velocity Setpoint
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/velocity
ROS-Service Type: core_api/VelocitySet, below is its description
#Request : expects velocity setpoint via vx,vy,vz
#Request : expects yaw_rate setpoint via yaw_rate (send yaw_rate_valid=true)
geometry_msgs/TwistStamped twist #deprecated, instead use vx,vy,vz,yaw_rate
float32 vx
float32 vy
float32 vz
float32 yaw_rate
float32 tolerance
bool async
bool relative
bool yaw_rate_valid
bool body_frame
#Response : return success=true, (if async=false && if setpoint reached before timeout = 30sec) || (if async=true && command sent to autopilot)
bool success
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: int Navigation::velocity_set(float vx, float vy, float vz, float yaw_rate = 0, float tolerance = 0, bool relative = false, bool async = false, bool yaw_rate_valid = false, bool body_frame = false)
Arguments:
vx,vy,vz: Velocity Setpoint in NED-Frame (in body-frame if body_frame=true)
yaw_rate: Yaw_rate Setpoint in radians/sec
yaw_rate_valid: Must be set to true, if yaw_rate setpoint is provided
tolerance: Acceptance radius in meters/s, default value=1.0m/s
relative: If true, velocity setpoints relative to current position is sent
async: If true, asynchronous mode is set
body_frame: If true, velocity setpoints are with respect to body frame
Returns: For async=true, returns 0 if the command is successfully sent to the vehicle, else returns 1. For async=false, returns 0 if the vehicle reaches given setpoint before timeout=30secs, else returns 1.
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.api.navigation
Function: velocity_set(self,vx, vy, vz, yaw_rate=0.0, tolerance=0.0, relative=False, async=False, yaw_rate_valid=False, body_frame=False):
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/velocity_set
call srv:
:float vx
:float vy
:float vz
:float yaw_rate
:float tolerance
:bool async
:bool relative
:bool yaw_rate_valid
:bool body_frame
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/velocity_set
call srv:
:float vx
:float vy
:float vz
:float yaw_rate
:float tolerance
:bool async
:bool relative
:bool yaw_rate_valid
:bool body_frame
response srv:
:bool success
:string message
This is a REST call for the API to give velocity setpoints.
Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/velocity_set'
JSON Request:
{
vx: Float,
vy: Float,
vz: Float,
yaw_rate: Float,
tolerance: Float,
async: Boolean,
relative: Boolean,
yaw_rate_valid : Boolean,
body_frame : Boolean
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API to give velocity setpoints.
Make sure you initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/velocity_set',
serviceType: 'core_api/VelocitySet'
Request:
{
vx: Float,
vy: Float,
vz: Float,
yaw_rate: Float,
tolerance: Float,
async: Boolean,
relative: Boolean,
yaw_valid : Boolean,
body_frame : Boolean
}
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytos/navigation/velocity_set "{vx: 0.5, vy: 0.2, vz: -0.1, yaw_rate: 0.1, tolerance: 0.0, async: false, relative: false, yaw_rate_valid: true, body_frame: false}"
#sends (vx,vy,vz)=(0.5,0.2,-0.1)(m/s), yaw_rate=0.1rad/s, relative=false, async=false, yaw_rate_valid=true, body_frame=false
#default value of tolerance=1.0m/s if left at 0
#include <cpp_api/navigation_bridge.h>
Navigation nav;
nav.velocity_set(1.0, 0.5, -1.0, 0.12, 0.5, false, false, true, false);
//sends (vx,vy,vz)=(1.0,0.5,-1.0)(m/s), yaw_rate=0.12rad/s, tolerance=0.5m/s, relative=false, async=false, yaw_rate_valid=true, body_frame=false
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
# wait for interface to initialize
time.sleep(3.0)
# fly towards right ( with respect to vehicle current heading)
drone.velocity_set(0, +2, 0, body_frame=True)
#include <core_api/PositionSet.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::PositionSet>("/<namespace>/navigation/position_set");
core_api::PositionSet srv;
srv.vx = 1.0;
srv.vy = 0.5;
srv.vz = -1.0;
srv.yaw_rate = 0.12;
srv.request.tolerance = 0.5;
srv.request.async = false;
srv.request.yaw_rate_valid = true;
srv.request.relative = false;
srv.request.body_frame = false;
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
//sends (vx,vy,vz)=(1.0,0.5,-1.0)(m/s), yaw_rate=0.12rad/s, tolerance=0.5m/s, relative=false, async=false, yaw_rate_valid=true, body_frame=false
import rospy
from core_api.srv import *
def setpoint_velocity(vx, vy, vz, yaw_rate, tolerance= 1.0, async = False, relative= False, yaw_rate_valid= False, body_frame= False):
rospy.wait_for_service('/<namespace>/navigation/velocity_set')
try:
handle = rospy.ServiceProxy('/<namespace>/navigation/velocity_set', VelocitySet)
# build message structure
req_msg = VelocitySetRequest(vx=vx, vy=vy, vz=vz, yaw_rate=yaw_rate, tolerance=tolerance, async=async, relative=relative, yaw_rate_valid=yaw_rate_valid, body_frame=body_frame)
resp = handle(req_msg)
return resp
except rospy.ServiceException, e:
rospy.logerr("vel set service call failed %s", e)
var msgdata={};
msgdata["vx"]=2.00;
msgdata["vy"]=3.00;
msgdata["vz"]=-1.00;
msgdata["yaw_rate"]=1.00;
msgdata["tolerance"]=2.00;
msgdata["async"]=true;
msgdata["relative"]=false;
msgdata["yaw_rate_valid"]=true;
msgdata["body_frame"]=false;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/navigation/velocity_set",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var velocitySet = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/velocity_set',
serviceType : 'core_api/VelocitySet'
});
var request = new ROSLIB.ServiceRequest({
vx: 2.00,
vy: 3.00,
vz: -1.00,
yaw_rate: 1.00,
tolerance: 2.00,
async: true,
relative: false,
yaw_rate_valid : true,
body_frame : false
});
velocitySet.callService(request, function(result) {
console.log('Result for service call on '
+ velocitySet.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
True
success: True
Success: True
{
success:True
}
{
success:True
}
Description:
This API gives linear (vx,vy,vz) and angular (yaw_rate) velocity setpoint to vehicle. Please check API usage section below before using API.
Parameters:
Following parameters are applicable for onboard C++ and Python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
vx, vy, vz | float | Velocity Setpoint in NED-Frame (in body-frame if body_frame=true) |
yaw_rate | float | Yaw rate Setpoint in rad/sec |
yaw_rate_valid | bool | Must be set to true, if yaw |
tolerance | float | Acceptance range in m/s, default value=1.0 m/s |
relative | bool | If true, velocity setpoints relative to current position is sent |
async | bool | If true, asynchronous mode is set |
body_frame | bool | If true, velocity setpoints are relative with respect to body frame |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
- Vehicle should be in GUIDED or OFFBOARD or API|POSCTL mode for this API to work.
- Vehicle should be armed for this API to work.
- Do not call this API when vehicle is grounded. Use take_off API first to get the vehicle in air.
- vx,vy,vz are velocity setpoints in 3 linear axes. Yaw rate is rate of angular rotation around Z axis. Right hand notation is used to find positive yaw direction.
- Effect of parameters:
- Async:
- True: The API call would return as soon as the command has been sent to the autopilot, irrespective of whether the vehicle has achieved the given velocity.
- False: The API call would wait for the function to return, which happens when either the velocity setpoint is reached or timeout=30secs is over.
- Relative:
- True: All setpoints (vx,vy,vz, yaw_rate) are calculated relative to current velocity. E.g. if vehicle is already flying in X direction with 1 m/s and a velocity call is placed for 2 m/s with relative= True then vehicle velocity target will change to 1+2 = 3 m/s.
- False: All setpoints (vx,vy,vz, yaw) are used as absolute velocity setpoints.
- Body_frame
- True: All the setpoints are converted to body frame.
- Front of vehicle : +vx
- Right of vehicle : +vy
- Down: +vz
- Yaw is calculated from front of vehicle.
- False: All the setpoints are converted to local NED (North, East, Down) frame. Yaw is calculated from North.
- Async:
- Either body_frame or relative flag can be set to true at a time. If both are set then only body_frame is effective.
- For yaw rate_ setpoint to be effective the yaw_rate_valid argument must be set to true.
- This API overrides any previous mission / navigation API being carried out.
- This API requires position lock. GPS, Optical Flow, VICON system can provide position data to vehicle.
- To provide only Yaw_rate setpoint use this API with x,y,z arguments set to 0, relative=True, yaw_valid=True
- Vehicle will keep flying in the direction specified by API if async= True. If async is False vehicle will stop after achieving target velocities in all directions. Make sure that you are handling such cases where vehicle might keep flying infinitely.
- Following parameters need to be manually configured according to vehicle frame.
- MPC_XY_VEL_MAX : Maximum horizontal velocity. For smaller and lighter this parameter could be set to value between 8 m/s to 15 m/s. For larger and heavier systems it is safer to set this value below 8 m/s.
- MPC_Z_VEL_MAX : Maximum vertical velocity. For smaller and lighter this parameter could be set to value between 3 m/s to 10 m/s. For larger and heavier systems it is safer to set this value below 8 m/s.
- In any case vehicle will not exceed these velocity limits. So velocity_set call with target velocity beyond these limits will never be returned successful in synchronous mode.
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/velocity_set
- Service Type:
core_api/VelocitySet
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/navigation/velocity_set
- JSON Request:
{ vx: Float, vy: Float, vz: Float, yaw_rate: Float, tolerance: Float, async: Boolean, relative: Boolean, yaw_rate_valid : Boolean, body_frame : Boolean }
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/velocity_set
- serviceType:
core_api/VelocitySet
Execute Script
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/exec_script
ROS-Service Type: core_api/ExecScript, below is its description
#Request : Expects name of the application to execute and the arguments to be passed to it
string app_name
string arguments
#Response : return success=true if script starts to get executed
bool success
string message
No CPP API is available for execution of onboard scripts.
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.API.navigation
Function: exec_script(app_name, arguments)
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/exec_script
call srv:
:string app_name
:string arguments
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/exec_script
call srv:
:string app_name
:string arguments
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/exec_script'
JSON Request:
{
app_name : String,
arguments : String
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/exec_script',
serviceType: 'core_api/ExecScript'
Request:
{
app_name : String,
arguments : String
}
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /<namespace>/navigation/exec_script "{}"
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
# execute onboard script with name in app_name and arguments to be passed with it as arguments
drone.exec_script(‘script’, ‘args’)
#include <core_api/ExecScript.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::ExecScript>("/<namespace>/navigation/exec_script");
core_api::ExecScript srv;
srv.request.app_name = "sample_script.sh";
srv.request.arguments = "arg1 arg2 arg3";
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
import rospy
from core_api.srv import *
script_name = "sample_script.sh"
sample_args = "arg1 arg2 arg3"
def exec_script(script_name, sample_args):
rospy.wait_for_service('/<namespace>/navigation/exec_script')
try:
handle = rospy.ServiceProxy('/<namespace>/navigation/exec_script', ExecScript)
resp = handle(app_name=script_name, arguments= sample_args)
return resp
except rospy.ServiceException, e:
rospy.logerr("service call failed %s", e)
var msgdata={};
msgdata["app_name"]='app12';
msgdata["arguments"]='2 45 4 run';
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/navigation/exec_script",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var execScript = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/exec_script',
serviceType : 'core_api/ExecScript'
});
var request = new ROSLIB.ServiceRequest({
app_name : 'app12',
arguments : '2 45 4 run'
});
execScript.callService(request, function(result) {
console.log('Result for service call on '
+ execScript.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
{'message': '', 'success': True}
message (string): Contains the error message if it is unable to run the script.
success (bool): true if action successful
success: True
Success: True
{
success:True
}
{
success:True
}
Description:
This API can run onboard executable scripts in python, shell, etc.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
app_name | string | Name of the script. Script should be present in /flyt/flytapps/onboard_user/install directory. |
arguments | string | arguments separated by space e.g. “arg1 arg2 arg3” |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
- Note that the executable should be present in
/flyt/userapps/onboard_user/install
directory.
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/exec_script
- Service Type:
ExecScript
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/navigation/exec_script
- JSON Request:
{ app_name : String, arguments : String }
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/exec_script
- serviceType:
core_api/ExecScript
Get Waypoints
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/waypoint_get
ROS-Service Type: core_api/WaypointGet, below is its description
# Request: NULL
# Returns success status and received count
bool success
string message
uint32 wp_received
mavros_msgs/Waypoint[] waypoints
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: int Navigation::waypoint_get(std::vector<mavros_msgs::Waypoint> &waypoints)
Arguments: waypoints: list of waypoints will be made available in this variable
Returns: returns 0 if the command is successfully sent to the vehicle
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: waypoint_get()
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/waypoint_get
call srv: Null
response srv:
:bool success
:uint32 wp_received
:mavros_msgs/Waypoint[] waypoints
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/waypoint_get
call srv: Null
response srv:
:bool success
:uint32 wp_received
:mavros_msgs/Waypoint[] waypoints
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/waypoint_get'
JSON Response:
{
success: Boolean,
message: String,
wp_recieved: Int,
waypoints: [
{
frame: Int 0/1/2/3/4,
command:Int 16/17/18/19/20/21/22,
is_current: Boolean,
autocontinue: Boolean,
param1: Float,
param2: Float,
param3: Float,
param4: Float,
x_lat: Float,
y_long: Float,
z_alt: Float
},
{},
{},...
]
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/waypoint_get',
serviceType: 'core_api/WaypointGet'
Response:
{
success: Boolean,
message: String,
wp_recieved: Int,
waypoints: [
{
frame: Int 0/1/2/3/4,
command:Int 16/17/18/19/20/21/22,
is_current: Boolean,
autocontinue: Boolean,
param1: Float,
param2: Float,
param3: Float,
param4: Float,
x_lat: Float,
y_long: Float,
z_alt: Float
},
{},
{},...
]
}
Example
rosservice call /flytos/navigation/waypoint_get "{}"
#include <cpp_api/navigation_bridge.h>
Navigation nav;
std::vector<mavros_msgs::Waypoint> &waypoints
nav.waypoint_get(waypoints);
std::cout<<"Number of waypoints received\t"<<waypoints.size()<<"\n";
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
# get list of current waypoints
wp = drone.waypoint_get()
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/navigation/waypoint_get",
success: function(data){
console.log(data.waypoints);
}
});
var waypointGet = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/waypoint_get',
serviceType : 'core_api/WaypointGet'
});
var request = new ROSLIB.ServiceRequest({});
waypointGet.callService(request, function(result) {
console.log('Result for service call on '
+ waypointGet.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: True
wp_received: 1
waypoints:
-
frame: 3
command: 16
is_current: True
autocontinue: True
param1: 0.0
param2: 0.0
param3: 0.0
param4: 0.0
x_lat: 18.6204299927
y_long: 73.903465271
z_alt: 50.0
0
{'wp_received': 2, 'message': '[INFO] Waypoint get Successful', 'success': True, 'waypoints': [{'autocontinue': True, 'frame': 0, 'command': 16, 'param4': 10.199999809265137, 'is_current': True, 'param2': 10.199999809265137, 'param1': 10.199999809265137, 'y_long': -122.08358764648438, 'param3': 0.0, 'x_lat': 7.429123401641846, 'z_alt': 112.61199951171875}, {'autocontinue': True, 'frame': 0, 'command': 16, 'param4': 10.199999809265137, 'is_current': False, 'param2': 10.199999809265137, 'param1': 10.199999809265137, 'y_long': -122.08329010009766, 'param3': 0.0, 'x_lat': 7.4294233322143555, 'z_alt': 112.61199951171875}]}
wp_received (int): Number of waypoints received
message (string): Contains error message
success (bool): true if action successful
waypoints (list): consists a list of dictionary, the dictionary consists of (frame, command, is_current, autocontinue, param1, param2, param3, param4, x_lat, y_long, z_alt)
{
success: True,
wp_recieved: 2,
waypoints: [{
frame: 3,
command:Int 16,
is_current: true,
autocontinue: true,
param1: 6.0,
param2: 7.0,
param3: 0.0,
param4: 0.0,
x_lat: 65.425532,
y_long: 18.542422,
z_alt: 25},{}]
}
{
success: True,
wp_recieved: 2,
waypoints: [{
frame: 3,
command:Int 16,
is_current: true,
autocontinue: true,
param1: 6.0,
param2: 7.0,
param3: 0.0,
param4: 0.0,
x_lat: 65.425532,
y_long: 18.542422,
z_alt: 25},{}]
}
Description:
This API returns list of current waypoints on autopilot.
Parameters:
Following parameters are applicable RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments: None
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
frame | int | The Frame in which the waypoints are given 0: Global 1: Local NED 2: Mission 3: Global Rel Alt |
command | int | defines the function of the waypoint 16: Waypoints 17: Loiter 18: Loiter Turns 19: Loiter time 20: Return to Launch 21: Land 22: Take Off |
is_current | bool | Set it as the first waypoint |
autocontinue | bool | continue to the next waypoint as soon as the current waypoint is achieved |
param1 | float | Time to stay at the location in sec. |
param2 | float | radius around the waypoint within which the waypoint is marked as done |
param3 | float | Orbit radius in meters |
param4 | float | Yaw/direction in degrees |
x_lat | float | Latitude |
y_long | float | Longitude |
z_alt | float | Relative altitude |
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/waypoint_get
- Service Type:
core_api/WaypointGet
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
GET http://<ip>/ros/<namespace>/navigation/waypoint_get
- JSON Response:
{ success: Boolean, message: String, wp_recieved: Int, waypoints: [{ frame: Int 0/1/2/3/4, command:Int 16/17/18/19/20/21/22, is_current: Boolean, autocontinue: Boolean, param1: Float, param2: Float, param3: Float, param4: Float, x_lat: Float, y_long: Float, z_alt: Float},{},{}...] } }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/waypoint_get
- serviceType:
core_api/WaypointGet
Set Waypoints
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/waypoint_set
ROS-Service Type: core_api/WaypointSet, below is its description
# Request: Waypoints to be sent to device
mavros_msgs/Waypoint[] waypoints
# Returns: success status and transfered count
bool success
string message
uint32 wp_transfered
// CPP API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from cpp.
Function Definition: int Navigation::waypoint_set(std::vector<mavros_msgs::Waypoint> waypoints)
Arguments:
waypoint: Array of waypoints to be sent to the autopilot
Returns: 0 if the land command is successfully sent to the vehicle, else returns 1.
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: waypoint_set(waypoints)
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/waypoint_set
call srv:
:mavros_msgs/Waypoint[] waypoints
response srv:
:bool success
:uint32 wp_transfered
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/waypoint_set
call srv:
:mavros_msgs/Waypoint[] waypoints
response srv:
:bool success
:uint32 wp_transfered
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/waypoint_set'
JSON Request:
{
waypoints:[
{
frame : [Int] 0/1/2/3/4,
command : [Int] 16/17/18/19/20/21/22,
is_current : [Boolean],
autocontinue : [Boolean],
param1 : [Float],
param2 : [Float],
param3 : [Float],
param4 : [Float],
x_lat : [Float],
y_long : [Float],
z_alt : [Float],
},
{},
{},...
]
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/waypoint_set',
serviceType: 'core_api/WaypointSet'
Request:
{
waypoints:[
{
frame : [Int] 0/1/2/3/4,
command : [Int] 16/17/18/19/20/21/22,
is_current : [Boolean],
autocontinue : [Boolean],
param1 : [Float],
param2 : [Float],
param3 : [Float],
param4 : [Float],
x_lat : [Float],
y_long : [Float],
z_alt : [Float],
},
{},
{},...
]
}
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytos/navigation/waypoint_set "waypoints:
- {frame: 0, command: 0, is_current: false, autocontinue: false, param1: 0.0, param2: 0.0,
param3: 0.0, param4: 0.0, x_lat: 0.0, y_long: 0.0, z_alt: 0.0}"
#include <cpp_api/navigation_bridge.h>
Navigation nav;
mavros_msgs::Waypoint waypoint;
std::vector<mavros_msgs::Waypoint> waypoints_array;
waypoint.frame = 3;
waypoint.command = 16;
waypoint.is_current = false;
waypoint.autocontinue = true;
waypoint.param1 = 0;
waypoint.param2 = 1;
waypoint.param3 = 0;
waypoint.param4 = 0;
waypoint.x_lat = 73.2154;
waypoint.x_long = 18.5472;
waypoint.z_alt = 5;
waypoints_array.push_back(waypoint)
nav.waypoint_set(waypoints_array);
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#for multiple waypoints
#list of waypoints to be constructed
wp4 = [{'frame': 0,
'command': 16,
'is_current': True,
'autocontinue': True,
'param1': 10.2,
'param2': 10.2,
'param3': 10.2,
'param4': 10.2,
'x_lat': x - 0.0002,
'y_long': y - 0.0002,
'z_alt': z + 10
},
{'frame': 0,
'command': 16,
'is_current': True,
'autocontinue': True,
'param1': 10.2,
'param2': 10.2,
'param3': 10.2,
'param4': 10.2,
'x_lat': x+0.0001,
'y_long': y + 0.0001,
'z_alt': z + 10
},
{'frame': 0,
'command': 16,
'is_current': True,
'autocontinue': True,
'param1': 10.2,
'param2': 10.2,
'param3': 10.2,
'param4': 10.2,
'x_lat': x,
'y_long': y,
'z_alt': z + 10
},
{'frame': 0,
'command': 16,
'is_current': True,
'autocontinue': True,
'param1': 10.2,
'param2': 10.2,
'param3': 10.2,
'param4': 10.2,
'x_lat': x + 0.0001,
'y_long': y + 0.0001,
'z_alt': z + 10
}]
# set list of current waypoints
drone.waypoint_set(wp4)
#for single waypoint
wp1 = {'frame': 0,
'command': 16,
'is_current': True,
'autocontinue': True,
'param1': 10.2,
'param2': 10.2,
'param3': 10.2,
'param4': 10.2,
'x_lat': x - 0.0002,
'y_long': y - 0.0002,
'z_alt': z + 10
}
#set list of current waypoints
drone.waypoint_set(wp1)
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
var msgdata=[];
msgdata[1]={};
msgdata[1]["frame"]=3;
msgdata[1]["command"]= 16;
msgdata[1]["is_current"]= false;
msgdata[1]["autocontinue"]= true;
msgdata[1]["param1"]= 0;
msgdata[1]["param2"]= 1;
msgdata[1]["param3"]= 0;
msgdata[1]["param4"]= 0;
msgdata[1]["x_lat"]= 73.2154;
msgdata[1]["y_long"]= 18.5472;
msgdata[1]["z_alt"]= 5;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/navigation/waypoint_set",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var waypointSet = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/waypoint_set',
serviceType : 'core_api/WaypointSet'
});
var request = new ROSLIB.ServiceRequest({
waypoints:[{
frame : [Int] 0/1/2/3/4,
command : [Int] 16/17/18/19/20/21/22,
is_current : [Boolean],
autocontinue : [Boolean],
param1 : [Float],
param2 : [Float],
param3 : [Float],
param4 : [Float],
x_lat : [Float],
y_long : [Float],
z_alt : [Float],
},{},{}... ]
});
waypointSet.callService(request, function(result) {
console.log('Result for service call on '
+ waypointSet.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: True
wp_transfered: 0
0
{'message': '[INFO] Waypoint set Successful', 'wp_transfered': 4, 'success': True}
wp_transfered (int): Number of waypoints transfered
message (string): Contains error message
success (bool): true if action successful
{
success:True
}
{
success:True
}
Description:
This API replaces current list of waypoints on autopilot with new list passed.
Parameters:
Following parameters are applicable in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
frame | int | The Frame in which the waypoints are given 0: Global 1: Local NED 2: Mission 3: Global Rel Alt |
command | int | defines the function of the waypoint 16: Waypoints 17: Loiter 18: Loiter Turns 19: Loiter time 20: Return to Launch 21: Land 22: Take Off |
is_current | bool | Set it as the first waypoint |
autocontinue | bool | continue to the next waypoint as soon as the current waypoint is achieved |
param1 | float | Time to stay at the location in sec. |
param2 | float | radius around the waypoint within which the waypoint is marked as done |
param3 | float | Orbit radius in meters |
param4 | float | Yaw/direction in degrees |
x_lat | float | Latitude |
y_long | float | Longitude |
z_alt | float | Relative altitude |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/waypoint_set
- Service Type:
WaypointSet
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/navigation/waypoint_set
- JSON Request:
{ waypoints:[{ frame : [Int] 0/1/2/3/4, command : [Int] 16/17/18/19/20/21/22, is_current : [Boolean], autocontinue : [Boolean], param1 : [Float], param2 : [Float], param3 : [Float], param4 : [Float], x_lat : [Float], y_long : [Float], z_alt : [Float], },{},{}... ] }
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/waypoint_set
- serviceType:
core_api/WaypointSet
Execute Waypoints
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/waypoint_execute
ROS-Service Type: core_api/waypointExecute, below is its description
#Request : Null
#Response : success = true if command sent successfully
bool success
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: int Navigation::waypoint_execute(void)
Arguments: None
Returns: returns 0 if the command is successfully sent to the vehicle
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: drone.waypoint_execute()
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/waypoint_execute
call srv: NULL
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/waypoint_execute
call srv: NULL
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/waypoint_execute'
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/waypoint_execute',
serviceType: 'core_api/WaypointExecute'
Response:
{ success: Boolean,
message: String, }
Example
rosservice call /flytsim/navigation/waypoint_execute "{}"
#include <cpp_api/navigation_bridge.h>
Navigation nav;
nav.waypoint_execute();
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#execute the waypoints
drone.waypoint_execute()
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/navigation/waypoint_execute",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var waypointExecute = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/waypoint_execute',
serviceType : 'core_api/WaypointExecute'
});
var request = new ROSLIB.ServiceRequest({});
waypointExecute.callService(request, function(result) {
console.log('Result for service call on '
+ waypointExecute.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
{'message': '[INFO] Waypoint Execution initiated', 'success': True}
message (string): Contains error message
success (bool): true if action successful
{
success:True
}
{
success:True
}
Description:
Exectute / resume current list of waypoints.
Parameters:
Following parameters are applicable in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
Note: Make sure you have a list of waypoints already set using set_waypoints
API before you give it execute_waypoint API call.
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/waypoint_execute
- Service Type:
WaypointExecute
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
GET http://<ip>/ros/<namespace>/navigation/waypoint_execute
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/waypoint_execute
- serviceType:
core_api/WaypointExecute
Clear Waypoints
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/waypoint_clear
ROS-Service Type: core_api/WaypointClear, below is its description
#Request : Null
#Response : success = true if command sent successfully
bool success
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: int Navigation::waypoint_clear(void)
Arguments: None
Returns: returns 0 if the command is successfully sent to the vehicle
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: waypoint_clear()
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/waypoint_clear
call srv: NULL
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/waypoint_clear
call srv: NULL
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/waypoint_clear'
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/waypoint_clear',
serviceType: 'core_api/WaypointClear'
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytos/navigation/waypoint_clear "{}"
#include <cpp_api/navigation_bridge.h>
Navigation nav;
nav.waypoint_clear();
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#clear the currently set waypoints
drone.waypoint_clear()
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/navigation/waypoint_clear",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var waypointClear = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/waypoint_clear',
serviceType : 'core_api/WaypointClear'
});
var request = new ROSLIB.ServiceRequest({});
waypointClear.callService(request, function(result) {
console.log('Result for service call on '
+ waypointClear.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
{'message': '[INFO] Waypoint clear Successful', 'success': True}
message (string): Contains error message
success (bool): true if action successful
{
success:True
}
{
success:True
}
Description:
Clear list of waypoints on autopilot.
Parameters:
Following parameters are applicable in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/waypoint_clear
- Service Type:
WaypointClear
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/navigation/waypoint_clear
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/waypoint_clear
- serviceType:
core_api/WaypointClear
Pause Waypoints
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/waypoint_pause
ROS-Service Type: core_api/WaypointPause, below is its description
#Request : Null
#Response : success = true if command sent successfully
bool success
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: int Navigation::waypoint_pause(void)
Arguments: None
Returns: returns 0 if the command is successfully sent to the vehicle
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: waypoint_pause()
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/waypoint_pause
call srv: NULL
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/waypoint_pause
call srv: NULL
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/waypoint_pause'
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/waypoint_pause',
serviceType: 'core_api/WaypointPause'
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytos/navigation/waypoint_pause "{}"
#include <cpp_api/navigation_bridge.h>
Navigation nav;
nav.waypoint_pause();
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#pause the waypoints mission
drone.waypoint_pause()
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/navigation/waypoint_pause",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var waypointPause = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/waypoint_pause',
serviceType : 'core_api/WaypointPause'
});
var request = new ROSLIB.ServiceRequest({});
waypointPause.callService(request, function(result) {
console.log('Result for service call on '
+ waypointPause.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
{'message': '[INFO] Waypoint Paused', 'success': True}
message (string): Contains error message
success (bool): true if action successful
{
success:True
}
{
success:True
}
Description:
This API pauses ongoing waypoint mission.
Parameters:
Following parameters are applicable in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/waypoint_pause
- Service Type:
WaypointPause
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
GET http://<ip>/ros/<namespace>/navigation/waypoint_pause
- JSON Response:
{ success: Boolean, message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/waypoint_pause
- serviceType:
core_api/WaypointPause
Set Current Waypoint
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/waypoint_set_current
ROS-Service Type: core_api/WaypointSetCurrent, below is its description
# Request: set current waypoint to index ( wp_seq ) in waypoint array
uint16 wp_seq
# Response: success if command sent successfully
bool success
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: int Navigation::waypoint_set_current(int waypoint_no)
Arguments:
waypoint_no: Index of waypoint to be set as current waypoint
Returns: returns 0 if the command is successfully sent to the vehicle
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.API.navigation
Function: waypoint_set_current(wp_seq)
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/waypoint_set_current
call srv: uint16 wp_seq
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/waypoint_set_current
call srv: uint16 wp_seq
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/waypoint_set_current'
JSON Request:
{
wp_seq: Int
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/waypoint_set_current',
serviceType: 'core_api/WaypointSetCurrent'
Request:
{
wp_seq: Int
}
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytsim/navigation/waypoint_set_current "wp_seq: 1"
#include <cpp_api/navigation_bridge.h>
Navigation nav;
int waypoint_no = 2;
nav.waypoint_set_current(waypoint_no);
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#setting the 2nd waypoint as the current waypoint
drone.waypoint_set_current(2)
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
var msgdata={};
msgdata["wp_seq"]=2;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/navigation/waypoint_set_current",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var waypointSetCurrent = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/waypoint_set_current',
serviceType : 'core_api/WaypointSetCurrent'
});
var request = new ROSLIB.ServiceRequest({
wp_seq: 2
});
waypointSetCurrent.callService(request, function(result) {
console.log('Result for service call on '
+waypointSetCurrent.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
{'message': '[INFO] Waypoint set_current Successful', 'success': True}
message (string): Contains error message
success (bool): true if action successful
{
success:True
}
{
success:True
}
Description:
Sets the waypoint Id specified, as the current waypoint from the list of already set wayopints.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
wp_seq | int | Id of the waypoint fro the list of set waypoints. |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/waypoint_set_current
- Service Type:
WaypointSetCurrent
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/navigation/waypoint_set_current
- JSON Request:
{ wp_seq: Int }
- JSON Response:
{ success: Boolean, message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/waypoint_set_current
- serviceType:
core_api/WaypointSetCurrent
Set Home
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/set_home
ROS-Service Type: core_api/SetHome, below is its description
#Request : Expects home position to be set by specifying Latitude, Longitude and altitude
#Request: If set_current is true, the current location of craft is set as home position
float64 lat
float64 lon
float64 alt
bool set_current
#Response : success=true if service called successfully
bool success
string message
No CPP API available.
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: set_home(lat, lon, alt, set_current=False)
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/set_home
call srv:
:float64 lat
:float64 lon
:float64 alt
:bool set_current
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/set_home
call srv:
:float64 lat
:float64 lon
:float64 alt
:bool set_current
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/set_home'
JSON Request:
{
lat: Float,
lon: Float,
alt: Float,
set_current : Boolean
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/set_home',
serviceType: 'core_api/SetHome'
Request:
{
lat: Float,
lon: Float,
alt: Float,
set_current : Boolean
}
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytsim/navigation/set_home "{lat: 73.25564541, lon: 18.2165632, alt: 2.0, set_current: false}"
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#set given location as home
drone.set_home(10.2, 10.2, 10.2)
#set current location as home
drone.set_home(0, 0, 0, True)
#include <core_api/SetHome.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::SetHome>("/<namespace>/navigation/set_home");
core_api::SetHome srv;
srv.request.lat = 73.25564541;
srv.request.lon = 18.2165632;
srv.request.alt = 2.00;
srv.request.set_current = false;
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
var msgdata={};
msgdata["lat"]=73.25564541;
msgdata["lon"]=18.36155;
msgdata["alt"]=2.00;
msgdata["set_current"]=true;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/navigation/set_home",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var setHome = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/set_home',
serviceType : 'core_api/SetHome'
});
var request = new ROSLIB.ServiceRequest({
lat: 73.12516255,
lon: 18.2165632,
alt: 2.00,
set_current : True
});
setHome.callService(request, function(result) {
console.log('Result for service call on '
+ setHome.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
{'message': '[INFO] Home Position successfully sent to vehicle', 'success': True}
message (string): Contains error message
success (bool): true if action successful
success: True
Success: True
{
success:True
}
{
success:True
}
Description:
Manually store a location as new home.
Parameters:
Following parameters are applicable for onboard C++ and Python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
lat,long,alt | float | Latitude, longitude and relative altitude |
set_current | boolean | if true uses current location and altitude of the device else uses the provided values. |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/set_home
- Service Type:
SetHome
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/navigation/set_home
- JSON Request:
{ lat: Float, lon: Float, alt: Float, set_current : Boolean }
- JSON Response:
{ success: Boolean, message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/set_home
- serviceType:
core_api/SetHome
RTL
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/navigation/rtl
ROS-Service Type: core_api/RTL, below is its description
#Request : NULL
#Response : returns success=true if RTL is activated
bool success
string message
// CPP API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from cpp.
Function Definition: int Navigation::rtl()
Arguments: None
Returns: 0 if the rtl command is successfully sent to the vehicle, else returns 1.
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.API.navigation
Function: rtl()
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/navigation/rtl
call srv: NULL
response srv:
:bool success
:string message
This is a REST call for the API to transition the vehicle to RTL mode. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/navigation/rtl'
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API to transition the vehicle to RTL mode. Make sure you
initialise the websocket using websocket initialising
API and and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/navigation/rtl',
serviceType: 'core_api/RTL'
Request:
{ }
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytos/navigation/rtl "{}"
#include <cpp_api/navigation_bridge.h>
Navigation nav;
nav.rtl();
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#trigger RTL mode
drone.rtl()
#include <core_api/RTL.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::RTL>("/<namespace>/navigation/rtl");
core_api::RTL srv;
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
import rospy
from core_api.srv import *
def rtl():
rospy.wait_for_service('/<namespace>/navigation/rtl')
try:
handle = rospy.ServiceProxy('/<namespace>/navigation/rtl', RTL)
resp = handle()
return resp
except rospy.ServiceException, e:
rospy.logerr("service call failed %s", e)
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/navigation/rtl",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var rtl = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/navigation/rtl',
serviceType : 'core_api/RTL'
});
var request = new ROSLIB.ServiceRequest({});
rtl.callService(request, function(result) {
console.log('Result for service call on '
+ rtl.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
{'message': '[INFO] RTL Triggered by FlytAPI', 'success': True}
message (string): Contains error message
success (bool): true if action successful
success: True
Success: True
{
success:True
}
{
success:True
}
Description:
Trigger RTL mode transition of the vehicle. Check API usage section below before using this API.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments: None
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
This API will transition the vehicle to RTL mode.
- This API can be used only in GUIDED or OFFBOARD or API|POSCTL mode.
- If any other navigation API is called when vehicle is in RTL mode, then RTL call be overridden by that API call.
- Make sure to configure the following parameters, before triggering this mode.
- RTL_RETURN_ALT : Altitude to fly back in RTL in meters.
- RTL_DESCEND_ALT : RTL Loiter altitude. Vehicle stays at this altitude above home position and starts to land if autolanding is allowed.
- RTL_LAND_DELAY : Delay after descend before landing in RTL mode. If set to -1 the system will not land but loiter at RTL_DESCEND_ALT.
- RTL_MIN_DIST : If the system is horizontally closer than this distance to home it will land straight on home instead of raising to the return altitude first.
ROS endpoint:
Navigation APIs in FlytOS are derived from / wrapped around the core navigation services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/navigation/rtl
- Service Type:
core_api/RTL
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
GET http://<ip>/ros/<namespace>/navigation/rtl
- JSON Response:
{ success: Boolean, message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/navigation/rtl
- serviceType:
core_api/RTL
Telemetry APIs
Get Attitude Quaternion
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Topic Name: /<namespace>/mavros/imu/data
ROS-Topic Type: sensor_msgs/Imu, below is its description
# Subscriber response : Attitude Quaternion
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Quaternion orientation
float64 x
float64 y
float64 z
float64 w
float64[9] orientation_covariance
geometry_msgs/Vector3 angular_velocity
float64 x
float64 y
float64 z
float64[9] angular_velocity_covariance
geometry_msgs/Vector3 linear_acceleration
float64 x
float64 y
float64 z
float64[9] linear_acceleration_covariance
// CPP API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from cpp.
Function Definition: sysSubscribe(Navigation::vehicle_attitude_quat,attitudeQuatCb);
Arguments:
vehicle_attitude_quat: This argument selects vehicle attitude quaternion topic to be subscribed
attitudeQuatCb: Callback function for the subscribed attitude messages
Returns: Vehicle attitude in quaternion notation in ros sensor_msgs::Imu message structure
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Quaternion orientation
float64 x
float64 y
float64 z
float64 w
float64[9] orientation_covariance
geometry_msgs/Vector3 angular_velocity
float64 x
float64 y
float64 z
float64[9] angular_velocity_covariance
geometry_msgs/Vector3 linear_acceleration
float64 x
float64 y
float64 z
float64[9] linear_acceleration_covariance
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.api.navigation
Function: get_attitude_quaternion()
Response: attitude_quaternion as described below.
class attitude_quaternion:
'''
Holds fields for Attitude data in Quaternion format
'''
x = 0.0
y = 0.0
z = 0.0
w = 0.0
rollspeed = 0.0
pitchspeed = 0.0
yawspeed = 0.0
This API supports single poll mode only.
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Topic
Name: /<namespace>/mavros/imu/data
Response Type: sensor_msgs/Imu
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Quaternion orientation
float64 x
float64 y
float64 z
float64 w
float64[9] orientation_covariance
geometry_msgs/Vector3 angular_velocity
float64 x
float64 y
float64 z
float64[9] angular_velocity_covariance
geometry_msgs/Vector3 linear_acceleration
float64 x
float64 y
float64 z
float64[9] linear_acceleration_covariance
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Topic
Name: /<namespace>/mavros/imu/data
Response Type: sensor_msgs/Imu
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Quaternion orientation
float64 x
float64 y
float64 z
float64 w
float64[9] orientation_covariance
geometry_msgs/Vector3 angular_velocity
float64 x
float64 y
float64 z
float64[9] angular_velocity_covariance
geometry_msgs/Vector3 linear_acceleration
float64 x
float64 y
float64 z
float64[9] linear_acceleration_covariance
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/mavros/imu/data'
JSON Response:
{
orientation:{
x: Float,
y: Float,
z: Float,
w: Float
},
angular_velocity:{
x: Float,
y: Float,
z: Float
},
linear_acceleration:{
x: Float,
y: Float,
z: Float
}
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/mavros/imu/data',
messageType: 'sensor_msgs/Imu'
Response:
{
orientation:{
x: Float,
y: Float,
z: Float,
w: Float
},
angular_velocity:{
x: Float,
y: Float,
z: Float
},
linear_acceleration:{
x: Float,
y: Float,
z: Float
}
}
Example
rostopic echo /flytos/mavros/imu/data
#include <cpp_api/navigation_bridge.h>
Navigation nav;
sensor_msgs::Imu att_quat;
void attitudeQuatCb(void *_att_quat)
{
att_quat = * (sensor_msgs::Imu*)(_att_quat);
}
nav.sysSubscribe(Navigation::vehicle_attitude_quat,attitudeQuatCb);
std::cout << att_quat << std::endl;
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
# wait for interface to initialize
time.sleep(3.0)
# Poll attitude euler data
att = drone.get_attitude_quaternion()
# Print the data
print att.x, att.y, att.z, att.w, att.rollspeed, att.pitchspeed, att.yawspeed
#include <sensor_msgs/Imu.h>
void attCallback(const sensor_msgs::ImuConstPtr &att)
{
att_data.orientation = att->orientation;
att_data.angular_velocity = att->angular_velocity;
att_data.linear_acceleration = att->linear_acceleration;
}
ros::NodeHandle nh;
sensor_msgs::Imu att_data;
ros::Subscriber sub = nh.subscribe("/<namespace>/mavros/imu/data", 1, attCallback);
import rospy
from sensor_msgs.msg import Imu
# setup a subscriber and associate a callback function which will be called every time topic is updated.
topic_sub = rospy.Subscriber("/<namespace>/mavros/imu/data"), Imu, topic_callback)
# define the callback function which will print the values every time topic is updated
def topic_callback(data):
x, y, z, w= data.orientation.x, data.orientation.y, data.orientation.z, data.orientation.w
print x, y, z, w
# unsubscribe from a topic
topic_sub.unregister() # unregister topic subscription
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/mavros/imu/data",
success: function(data){
console.log(data);
}
});
var imuData = new ROSLIB.Topic({
ros : ros,
name : '/<namespace>/mavros/imu/data',
messageType : 'sensor_msgs/Imu',
throttle_rate: 200
});
imuData.subscribe( function(message) {
console.log(message.data);
});
Example response
header:
seq: 112
stamp:
secs: 1489476690
nsecs: 278339713
frame_id: fcu
orientation:
x: -0.00593215392702
y: 0.00396701722143
z: 0.988477372188
w: 0.151200386894
orientation_covariance: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
angular_velocity:
x: 0.00392133416608
y: -0.000496329041198
z: -0.000130902582896
angular_velocity_covariance: [1.2184696791468346e-07, 0.0, 0.0, 0.0, 1.2184696791468346e-07, 0.0, 0.0, 0.0, 1.2184696791468346e-07]
linear_acceleration:
x: -0.1176798
y: -0.4314926
z: -9.81645665
linear_acceleration_covariance: [8.999999999999999e-08, 0.0, 0.0, 0.0, 8.999999999999999e-08, 0.0, 0.0, 0.0, 8.999999999999999e-08]
instance of sensor_msgs::Imu class
instance of class attitude_quaternion
instance of sensor_msgs::Imu class
instance of sensor_msgs.msg.Imu class
{
orientation:{
x: Float,
y: Float,
z: Float,
w: Float},
angular_velocity:{
x: Float,
y: Float,
z: Float},
linear_acceleration:{
x: Float,
y: Float,
z: Float}
}
{
orientation:{
x: Float,
y: Float,
z: Float,
w: Float},
angular_velocity:{
x: Float,
y: Float,
z: Float},
linear_acceleration:{
x: Float,
y: Float,
z: Float}
}
Description:
This API subscribes/polls attitude data (angle and angular rate) in quaternion. Please check API usage section below before using API.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Response:
Parameter | Type | Description |
---|---|---|
x | float | x vector. |
y | float | y vector. |
z | float | z vector. |
w | float | w vector. |
rollspeed | float | roll rate in radians/sec, NED frame. |
pitchspeed | float | pitch rate in radians/sec, NED frame. |
yawspeed | float | yaw rate in radians/sec, NED frame. |
API usage information:
- This API provides orientation in quaternion and angular velocity
ROS endpoint:
All the autopilot state / payload data in FlytOS is shared by ROS topics. Onboard topic subscribers in rospy / roscpp can subscribe to these topics. Take a look at roscpp and rospy API definition for response message structure.
- Type:
Ros Topic
- Name:
/<namespace>/mavros/imu/data
- Response Type:
sensor_msgs/Imu
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice. All RESTful APIs can poll the data. For telemetry mode (continuous data stream) use websocket APIs.
- URL:
GET http://<ip>/ros/<namespace>/mavros/imu/data
- JSON Response:
{ orientation:{ x: Float, y: Float, z: Float, w: Float}, angular_velocity:{ x: Float, y: Float, z: Float}, linear_acceleration:{ x: Float, y: Float, z: Float} }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/mavros/imu/data
- messageType:
sensor_msgs/Imu
Get Attitude Euler Data
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Topic Name: /<namespace>/mavros/imu/data_euler
ROS-Topic Type: geometry_msgs/TwistStamped, below is its description
#Subscriber response : Euler angles
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Twist twist
geometry_msgs/Vector3 linear
float64 x
float64 y
float64 z
geometry_msgs/Vector3 angular
float64 x
float64 y
float64 z
// CPP API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from cpp.
Function Definition: sysSubscribe(Navigation::vehicle_attitude_euler,attitudeEulerCb);
Arguments:
vehicle_attitude_euler: This argument selects vehicle attitude euler topic to be subscribed
attitudeEulerCb: Callback function for the subscribed attitude messages
Returns: Vehicle attitude in euler notation in ros geometry_msgs::TwistStamped message structure
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Twist twist
geometry_msgs/Vector3 linear
float64 x
float64 y
float64 z
geometry_msgs/Vector3 angular
float64 x
float64 y
float64 z
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.api.navigation
Function: get_attitude_euler()
Response: attitude_euler_object as described below.
class attitude_euler:
'''
Holds fields for Attitude data in Euler Angles
'''
roll = 0.0
pitch = 0.0
yaw = 0.0
rollspeed = 0.0
pitchspeed = 0.0
yawspeed = 0.0
This API support single poll mode only.
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Topic
Name: /<namespace>/mavros/imu/data_euler
Response Type:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Twist twist
geometry_msgs/Vector3 linear
float64 x
float64 y
float64 z
geometry_msgs/Vector3 angular
float64 x
float64 y
float64 z
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Topic
Name: /<namespace>/mavros/imu/data_euler
Response Type:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Twist twist
geometry_msgs/Vector3 linear
float64 x
float64 y
float64 z
geometry_msgs/Vector3 angular
float64 x
float64 y
float64 z
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/mavros/imu/data_euler'
JSON Response:
{
twist:{
linear:{
x: Float,
y: Float,
z: Float
},
angular:{
x: Float,
y: Float,
z: Float
}
}
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/mavros/imu/data_euler',
messageType: 'geometry_msgs/TwistStamped'
Response:
{
twist:{
linear:{
x: Float,
y: Float,
z: Float
},
angular:{
x: Float,
y: Float,
z: Float
}
}
}
Example
rostopic echo /flytpods/mavros/imu/data_euler
#include <cpp_api/navigation_bridge.h>
Navigation nav;
geometry_msgs::TwistStamped att_euler;
void attitudeEulerCb(void *_att_euler)
{
att_euler = * (geometry_msgs::TwistStamped*)(_att_euler);
std::cout<<"\nroll \t\tpitch \t\tyaw \t\trollspeed \tpitchspeed \tyawspeed";
std::cout<<"\n"<<att_euler.twist.linear.x<<"\t"<<att_euler.twist.linear.y<<"\t"<<att_euler.twist.linear.z;
std::cout<<"\t"<<att_euler.twist.angular.x<<"\t"<<att_euler.twist.angular.y<<"\t"<<att_euler.twist.angular.z;
fflush(stdout);
}
int main(int argc, char *argv[])
{
nav.sysSubscribe(Navigation::vehicle_attitude_euler,attitudeEulerCb);
while(ros::ok()){
sleep(0.2);
}
}
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
# wait for interface to initialize
time.sleep(3.0)
# Poll attitude euler data
att = drone.get_attitude_euler()
# Print the data
print att.roll, att.pitch, att.yaw, att.rollspeed, att.pitchspeed, att.yawspeed
#include <geometry_msgs/TwistStamped.h>
void attCallback(const geometry_msgs::TwistStampedConstPtr &att)
{
std::cout<<"\nroll \t\tpitch \t\tyaw \t\trollspeed \tpitchspeed \tyawspeed";
std::cout<<"\n"<<att->twist.linear.x<<"\t"<<att->twist.linear.y<<"\t"<<att->twist.linear.z;
std::cout<<"\t"<<att->twist.angular.x<<"\t"<<att->twist.angular.y<<"\t"<<att->twist.angular.z;
fflush(stdout);
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "att_euler_cb");
ros::NodeHandle nh;
ros::Subscriber sub = nh.subscribe("/<namespace>/mavros/imu/data_euler", 1, attCallback);
ros::spin();
return 0;
}
import rospy
from geometry_msgs.msg import TwistStamped
# setup a subscriber and associate a callback function which will be called every time topic is updated.
topic_sub = rospy.Subscriber("/<namespace>/mavros/imu/data_euler"), TwistStamped, topic_callback)
# define the callback function which will print the values every time topic is updated
def topic_callback(data):
roll, pitch, yaw = data.twist.linear.x, data.twist.linear.y, data.twist.linear.z
print roll, pitch, yaw
# unsubscribe from a topic
topic_sub.unregister() # unregister topic subscription
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/mavros/imu/data_euler",
success: function(data){
console.log(data);
}
});
var imuEulerData = new ROSLIB.Topic({
ros : ros,
name : '/<namespace>/mavros/imu/data_euler',
messageType : 'geometry_msgs/TwistStamped'
});
imuEulerData.subscribe(function(message) {
console.log(message.data);
});
Example response
header:
seq: 4090
stamp:
secs: 1489483667
nsecs: 763130240
frame_id: fcu
twist:
linear:
x: -0.0357596799731
y: -0.0206729210913
z: -1.89611303806
angular:
x: -0.00441705761477
y: 0.00617094011977
z: -0.000732765707653
instance of geometry_msgs::TwistStamped class
header:
seq: 2041
stamp:
secs: 1492705227
nsecs: 960368337
frame_id: fcu
twist:
linear:
x: -0.00561133073643
y: -0.00531742209569
z: -0.0351081602275
angular:
x: 0.00158157129772
y: 0.001551638823
z: 0.00154603447299
instance of class
class attitude_euler:
'''
Holds fields for Attitude data in Euler Angles
'''
roll = 0.0
pitch = 0.0
yaw = 0.0
rollspeed = 0.0
pitchspeed = 0.0
yawspeed = 0.0
instance of geometry_msgs::TwistStamped class
header:
seq: 2041
stamp:
secs: 1492705227
nsecs: 960368337
frame_id: fcu
twist:
linear:
x: -0.00561133073643
y: -0.00531742209569
z: -0.0351081602275
angular:
x: 0.00158157129772
y: 0.001551638823
z: 0.00154603447299
instance of gemometry_msgs.msg.TwistStamped class
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Twist twist
geometry_msgs/Vector3 linear
float64 x
float64 y
float64 z
geometry_msgs/Vector3 angular
float64 x
float64 y
float64 z
{
twist:{
linear:{
x: Float,
y: Float,
z: Float},
angular:{
x: Float,
y: Float,
z: Float}
}
{
twist:{
linear:{
x: Float,
y: Float,
z: Float},
angular:{
x: Float,
y: Float,
z: Float}
}
Description:
This API subscribes/polls attitude data (angle and angular rate) in euler angles. Please check API usage section below before using API.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Response:
Parameter | Type | Description |
---|---|---|
roll | float | roll angle in radians, NED frame. |
pitch | float | pitch angle in radians, NED frame. |
yaw | float | yaw angle in radians, NED frame. |
rollspeed | float | roll rate in radians/sec, NED frame. |
pitchspeed | float | pitch rate in radians/sec, NED frame. |
yawspeed | float | yaw rate in radians/sec, NED frame. |
API usage information:
- This API provides roll, pitch, yaw, rollspeed, pitchspeed, yawspeed information.
- Data returned is in NED frame.
ROS endpoint:
All the autopilot state / payload data in FlytOS is shared by ROS topics. Onboard topic subscribers in rospy / roscpp can subscribe to these topics. Take a look at roscpp and rospy API definition for response message structure.
- Type:
Ros Topic
- Name:
/<namespace>/mavros/imu/data_euler
- Response Type:
geometry_msgs/TwistStamped
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice. All RESTful APIs can poll the data. For telemetry mode (continuous data stream) use websocket APIs.
- URL:
GET http://<ip>/ros/<namespace>/mavros/imu/data_euler
- JSON Response:
{ twist:{ linear:{ x: Float, y: Float, z: Float }, angular:{ x: Float, y: Float, z: Float } }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/mavros/imu/data_euler
- messageType:
geometry_msgs/TwistStamped
Get Local Position
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Topic Name: /<namespace>/mavros/imu/local_position/local
ROS-Topic Type: geometry_msgs/TwistStamped, below is its description
#Subscriber response : Euler angles
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Twist twist
geometry_msgs/Vector3 linear
float64 x
float64 y
float64 z
geometry_msgs/Vector3 angular
float64 x
float64 y
float64 z
// CPP API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from cpp.
Function Definition: sysSubscribe(Navigation::local_position,lposCb);
Arguments:
local_position: This argument selects local position topic to be subscribed
lposCb: Callback function for the subscribed local position messages
Returns: local position in ros geometry_msgs::TwistStamped message structure
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Twist twist
geometry_msgs/Vector3 linear
float64 x
float64 y
float64 z
geometry_msgs/Vector3 angular
float64 x
float64 y
float64 z
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.api.navigation
Function: get_local_position()
Response: local_position as described below.
class local_position:
'''
Holds fields for local position
'''
x = 0.0
y = 0.0
z = 0.0
vx = 0.0
vy = 0.0
vz = 0.0
This API support single poll mode only.
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Topic
Name: /<namespace>/mavros/local_position/local
Response Type:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Twist twist
geometry_msgs/Vector3 linear
float64 x
float64 y
float64 z
geometry_msgs/Vector3 angular
float64 x
float64 y
float64 z
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Topic
Name: /<namespace>/mavros/local_position/local
Response Type:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
geometry_msgs/Twist twist
geometry_msgs/Vector3 linear
float64 x : x position
float64 y : y position
float64 z : z position
geometry_msgs/Vector3 angular
float64 x : linear acceleration along x axis
float64 y : linear acceleration along y axis
float64 z : linear acceleration along z axis
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/mavros/local_position/local'
JSON Response:
{ twist:{
linear:{
x: Float,
y: Float,
z: Float},
angular:{
x: Float,
y: Float,
z: Float}
}}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/mavros/local_position/local',
messageType: 'geometry_msgs/TwistStamped'
Response:
{ twist:{
linear:{
x: Float,
y: Float,
z: Float},
angular:{
x: Float,
y: Float,
z: Float}
}}
Example
rostopic echo /flytos/mavros/local_position/local
#include <cpp_api/navigation_bridge.h>
Navigation nav;
geometry_msgs::TwistStamped lpos;
void lposCb(void *_lpos)
{
lpos = * (geometry_msgs::TwistStamped*)(_lpos);
}
nav.sysSubscribe(Navigation::local_position,lposCb);
std::cout << lpos << std::endl;
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
# wait for interface to initialize
time.sleep(3.0)
# Poll data
pos = drone.get_local_position()
# Print the data
print pos.x, pos.vx
#include <geometry_msgs/TwistStamped>
void lposCallback(const geometry_msgs::TwistStampedConstPtr &lpos)
{
lpos_data.twist.linear = lpos->twist.linear;
lpos_data.twist.angular = lpos->twist.angular;
}
ros::NodeHandle nh;
geometry_msgs::TwistStamped lpos_data;
ros::Subscriber sub = nh.subscribe("/<namespace>/mavros/local_position/local", 1, lposCallback);
import rospy
from geometry_msgs.msg import TwistStamped
# setup a subscriber and associate a callback function which will be called every time topic is updated.
topic_sub = rospy.Subscriber("/<namespace>/mavros/local_position/local"), TwistStamped, topic_callback)
# define the callback function which will print the values every time topic is updated
def topic_callback(data):
x, y, z = data.twist.linear.x, data.twist.linear.y, data.twist.linear.z
print x, y, z
# unsubscribe from a topic
topic_sub.unregister() # unregister topic subscription
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/mavros/local_position/local",
success: function(data){
console.log(data);
}
});
var lpos = new ROSLIB.Topic({
ros : ros,
name : '/<namespace>/mavros/local_position/local',
messageType : 'geometry_msgs/TwistStamped',
throttle_rate: 200
});
lpos.subscribe(function(message) {
console.log(message.twist);
});
Example response
header:
seq: 2589
stamp:
secs: 1489483590
nsecs: 137668160
frame_id: fcu
twist:
linear:
x: 0.0
y: 0.0
z: 2.52842187881
angular:
x: 0.000367590633687
y: 0.001967407763
z: 0.0995724499226
instance of geometry_msgs::TwistStamped class
instance of class local_position
instance of geometry_msgs::TwistStamped class
instance of gemometry_msgs.msg.TwistStamped class
{
twist:{
linear:{
x: Float,
y: Float,
z: Float},
angular:{
x: Float,
y: Float,
z: Float}
}}
{
twist:{
linear:{
x: Float,
y: Float,
z: Float},
angular:{
x: Float,
y: Float,
z: Float}
}}
Description:
This API subscribes/polls linear position, velocity data in NED frame. Check API usage section below before using API.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Response:
Parameter | Type | Description |
---|---|---|
x | float | x position in local NED frame. |
y | float | y position in local NED frame. |
z | float | z position in local NED frame. |
vx | float | x velocity in local NED frame. |
vy | float | y velocity in local NED frame. |
vz | float | z velocity in local NED frame. |
API usage information:
- This API provides linear position and linear velocity.
- Data returned is in NED frame.
- Be careful when using z data obtained into takeoff or position setpoint APIs. These API’s may expect z values relative to ground. But the current local position that you get has negative z values for position above ground.
ROS endpoint:
All the autopilot state / payload data in FlytOS is shared by ROS topics. Onboard topic subscribers in rospy / roscpp can subscribe to these topics. Take a look at roscpp and rospy API definition for response message structure.
- Type:
Ros Topic
- Name:
/<namespace>/mavros/local_position/local
- Response Type:
geometry_msgs/TwistStamped
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice. All RESTful APIs can poll the data. For telemetry mode (continuous data stream) use websocket APIs.
- URL:
GET http://<ip>/ros/<namespace>/mavros/local_position/local
- JSON Response:
{ twist:{ linear:{ x: Float, y: Float, z: Float }, angular:{ x: Float, y: Float, z: Float } } }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/mavros/local_position/local
- messageType:
geometry_msgs/TwistStamped
Get Global Position
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Topic Name: /<namespace>/mavros/global_position/global
ROS-Topic Type: sensor_msgs/NavSatFix, below is its description
#Subscriber response : GPS pos
Response structure:
uint8 COVARIANCE_TYPE_UNKNOWN=0
uint8 COVARIANCE_TYPE_APPROXIMATED=1
uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN=2
uint8 COVARIANCE_TYPE_KNOWN=3
std_msgs/Header header
uint32 seq
time stamp
string frame_id
sensor_msgs/NavSatStatus status
int8 STATUS_NO_FIX=-1
int8 STATUS_FIX=0
int8 STATUS_SBAS_FIX=1
int8 STATUS_GBAS_FIX=2
uint16 SERVICE_GPS=1
uint16 SERVICE_GLONASS=2
uint16 SERVICE_COMPASS=4
uint16 SERVICE_GALILEO=8
int8 status
uint16 service
float64 latitude : latitude
float64 longitude : longitude
float64 altitude : altitude MSL
float64[9] position_covariance
uint8 position_covariance_type
// CPP API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from cpp.
Function Definition: sysSubscribe(Navigation::global_position,gposCb);
Arguments:
global_position: This argument selects global position topic to be subscribed
gposCb: Callback function for the subscribed global position messages
Returns: global position in ros sensor_msgs::NavSatFix message structure
uint8 COVARIANCE_TYPE_UNKNOWN=0
uint8 COVARIANCE_TYPE_APPROXIMATED=1
uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN=2
uint8 COVARIANCE_TYPE_KNOWN=3
std_msgs/Header header
uint32 seq
time stamp
string frame_id
sensor_msgs/NavSatStatus status
int8 STATUS_NO_FIX=-1
int8 STATUS_FIX=0
int8 STATUS_SBAS_FIX=1
int8 STATUS_GBAS_FIX=2
uint16 SERVICE_GPS=1
uint16 SERVICE_GLONASS=2
uint16 SERVICE_COMPASS=4
uint16 SERVICE_GALILEO=8
int8 status
uint16 service
float64 latitude : latitude
float64 longitude : longitude
float64 altitude : altitude MSL
float64[9] position_covariance
uint8 position_covariance_type
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.api.navigation
Function: get_global_position()
Response: glob_position as described below.
class glob_position:
'''
Holds fields for global position
'''
lat = 0.0
lon = 0.0
alt = 0.0
This API supports single poll mode only.
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Topic
Name: /<namespace>/mavros/global_position/global
Response Type: sensor_msgs/NavSatFix
uint8 COVARIANCE_TYPE_UNKNOWN=0
uint8 COVARIANCE_TYPE_APPROXIMATED=1
uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN=2
uint8 COVARIANCE_TYPE_KNOWN=3
std_msgs/Header header
uint32 seq
time stamp
string frame_id
sensor_msgs/NavSatStatus status
int8 STATUS_NO_FIX=-1
int8 STATUS_FIX=0
int8 STATUS_SBAS_FIX=1
int8 STATUS_GBAS_FIX=2
uint16 SERVICE_GPS=1
uint16 SERVICE_GLONASS=2
uint16 SERVICE_COMPASS=4
uint16 SERVICE_GALILEO=8
int8 status
uint16 service
float64 latitude : latitude
float64 longitude : longitude
float64 altitude : altitude MSL
float64[9] position_covariance
uint8 position_covariance_type
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Topic
Name: /<namespace>/mavros/global_position/global
Response Type: sensor_msgs/NavSatFix
uint8 COVARIANCE_TYPE_UNKNOWN=0
uint8 COVARIANCE_TYPE_APPROXIMATED=1
uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN=2
uint8 COVARIANCE_TYPE_KNOWN=3
std_msgs/Header header
uint32 seq
time stamp
string frame_id
sensor_msgs/NavSatStatus status
int8 STATUS_NO_FIX=-1
int8 STATUS_FIX=0
int8 STATUS_SBAS_FIX=1
int8 STATUS_GBAS_FIX=2
uint16 SERVICE_GPS=1
uint16 SERVICE_GLONASS=2
uint16 SERVICE_COMPASS=4
uint16 SERVICE_GALILEO=8
int8 status
uint16 service
float64 latitude : latitude
float64 longitude : longitude
float64 altitude : altitude MSL
float64[9] position_covariance
uint8 position_covariance_type
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/mavros/global_position/global'
JSON Response:
{ latitude: Float,
longitude: Float,
altitude: Float}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/mavros/global_position/global',
messageType: 'sensor_msgs/NavSatFix'
Response:
{
latitude: Float,
longitude: Float,
altitude: Float
}
Example
rostopic echo /flytos/mavros/global_position/global
#include <cpp_api/navigation_bridge.h>
Navigation nav;
sensor_msgs::NavSatFix gpos;
void gposCb(void *_gpos)
{
gpos = * (sensor_msgs::NavSatFix*)(_gpos);
}
nav.sysSubscribe(Navigation::global_position,gposCb);
std::cout << gpos << std::endl;
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
# wait for interface to initialize
time.sleep(3.0)
# Poll data
gpos = drone.get_global_position()
# Print the data
print gpos.lat, gpos.lon, gpos.alt
#include <sensor_msgs/NavSatFix.h>
void gposCallback(const sensor_msgs::NavSatFixConstPtr &gpos)
{
gpos_data.latitude = gpos->latitude;
gpos_data.longitude = gpos->longitude;
gpos_data.altitude = gpos->altitude;
}
ros::NodeHandle nh;
sensor_msgs::NavSatFix gpos_data;
ros::Subscriber sub = nh.subscribe("/<namespace>/mavros/global_position/global", 1, gposCallback);
import rospy
from sensor_msgs.msg import NavSatFix
# setup a subscriber and associate a callback function which will be called every time topic is updated.
topic_sub = rospy.Subscriber("/<namespace>/mavros/global_position/global"), NavSatFix, topic_callback)
# define the callback function which will print the values every time topic is updated
def topic_callback(data):
lat, lon, alt = data.latitude, data.longitude, data.altitude
print lat, lon, alt
# unsubscribe from a topic
topic_sub.unregister() # unregister topic subscription
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/mavros/global_position/global",
success: function(data){
console.log(data);
}
});
var gpsData = new ROSLIB.Topic({
ros : ros,
name : '/<namespace>/mavros/global_position/global',
messageType : 'sensor_msgs/NavSatFix'
});
gpsData.subscribe(function(message) {
console.log(message.data);
});
Example response
success: true
instance of sensor_msgs::NavSatFix class
instance of class glob_position
instance of sensor_msgs::NavSatFix class
instance of sensor_msgs.msg.NavSatFix class
{
latitude: Float,
longitude: Float,
altitude: Float
}
{
latitude: Float,
longitude: Float,
altitude: Float
}
Description:
This API subscribes/polls position data in global coordinate system. Please check API usage section below before using API.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Response:
Parameter | Type | Description |
---|---|---|
lat | float | latitude in global coordinate system WGS84 |
lon | float | longitude in global coordinate system WGS84 |
alt | float | altitude from MSL (mean sea level) in meters. |
API usage information:
- This API provides GPS coordinates and altitude at current location
- Altitude value returned is relative to MSL (mean sea level).
- Be careful when using altitude data obtained from this API into takeoff or position setpoint APIs. These API’s expect z values in local frame.
ROS endpoint:
All the autopilot state / payload data in FlytOS is shared by ROS topics. Onboard topic subscribers in rospy / roscpp can subscribe to these topics. Take a look at roscpp and rospy API definition for response message structure.
- Type:
Ros Topic
- Name:
/<namespace>/mavros/global_position/global
- Response Type:
sensor_msgs/NavSatFix
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice. All RESTful APIs can poll the data. For telemetry mode (continuous data stream) use websocket APIs.
- URL:
GET http://<ip>/ros/<namespace>/mavros/global_position/global
- JSON Response:
{ latitude: Float, longitude: Float, altitude: Float }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/mavros/global_position/global
- messageType:
sensor_msgs/NavSatFix
Get Battery Status
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Topic Name: /<namespace>/mavros/battery
ROS-Topic Type: sensor_msgs/BatteryState, below is its description
#Subscriber response : Battery Status
Response structure:
uint8 POWER_SUPPLY_STATUS_UNKNOWN=0
uint8 POWER_SUPPLY_STATUS_CHARGING=1
uint8 POWER_SUPPLY_STATUS_DISCHARGING=2
uint8 POWER_SUPPLY_STATUS_NOT_CHARGING=3
uint8 POWER_SUPPLY_STATUS_FULL=4
uint8 POWER_SUPPLY_HEALTH_UNKNOWN=0
uint8 POWER_SUPPLY_HEALTH_GOOD=1
uint8 POWER_SUPPLY_HEALTH_OVERHEAT=2
uint8 POWER_SUPPLY_HEALTH_DEAD=3
uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE=4
uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE=5
uint8 POWER_SUPPLY_HEALTH_COLD=6
uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE=7
uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE=8
uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN=0
uint8 POWER_SUPPLY_TECHNOLOGY_NIMH=1
uint8 POWER_SUPPLY_TECHNOLOGY_LION=2
uint8 POWER_SUPPLY_TECHNOLOGY_LIPO=3
uint8 POWER_SUPPLY_TECHNOLOGY_LIFE=4
uint8 POWER_SUPPLY_TECHNOLOGY_NICD=5
uint8 POWER_SUPPLY_TECHNOLOGY_LIMN=6
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32 voltage
float32 current
float32 charge
float32 capacity
float32 design_capacity
float32 percentage
uint8 power_supply_status
uint8 power_supply_health
uint8 power_supply_technology
bool present
float32[] cell_voltage
string location
string serial_number
Not Implemented
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.API.navigation
Function: get_battery_status()
Response: battery_status as described below.
class battery_status:
'''
Holds data for battery status
'''
voltage = 0.0
current = 0.0
remaining = 0.0
This API supports single poll mode only.
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Topic
Name: /<namespace>/mavros/battery
Response Type: sensor_msgs/BatteryState
uint8 POWER_SUPPLY_STATUS_UNKNOWN=0
uint8 POWER_SUPPLY_STATUS_CHARGING=1
uint8 POWER_SUPPLY_STATUS_DISCHARGING=2
uint8 POWER_SUPPLY_STATUS_NOT_CHARGING=3
uint8 POWER_SUPPLY_STATUS_FULL=4
uint8 POWER_SUPPLY_HEALTH_UNKNOWN=0
uint8 POWER_SUPPLY_HEALTH_GOOD=1
uint8 POWER_SUPPLY_HEALTH_OVERHEAT=2
uint8 POWER_SUPPLY_HEALTH_DEAD=3
uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE=4
uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE=5
uint8 POWER_SUPPLY_HEALTH_COLD=6
uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE=7
uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE=8
uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN=0
uint8 POWER_SUPPLY_TECHNOLOGY_NIMH=1
uint8 POWER_SUPPLY_TECHNOLOGY_LION=2
uint8 POWER_SUPPLY_TECHNOLOGY_LIPO=3
uint8 POWER_SUPPLY_TECHNOLOGY_LIFE=4
uint8 POWER_SUPPLY_TECHNOLOGY_NICD=5
uint8 POWER_SUPPLY_TECHNOLOGY_LIMN=6
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32 voltage
float32 current
float32 charge
float32 capacity
float32 design_capacity
float32 percentage
uint8 power_supply_status
uint8 power_supply_health
uint8 power_supply_technology
bool present
float32[] cell_voltage
string location
string serial_number
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Topic
Name: /<namespace>/mavros/battery
Response Type: sensor_msgs/BatteryState
uint8 POWER_SUPPLY_STATUS_UNKNOWN=0
uint8 POWER_SUPPLY_STATUS_CHARGING=1
uint8 POWER_SUPPLY_STATUS_DISCHARGING=2
uint8 POWER_SUPPLY_STATUS_NOT_CHARGING=3
uint8 POWER_SUPPLY_STATUS_FULL=4
uint8 POWER_SUPPLY_HEALTH_UNKNOWN=0
uint8 POWER_SUPPLY_HEALTH_GOOD=1
uint8 POWER_SUPPLY_HEALTH_OVERHEAT=2
uint8 POWER_SUPPLY_HEALTH_DEAD=3
uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE=4
uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE=5
uint8 POWER_SUPPLY_HEALTH_COLD=6
uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE=7
uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE=8
uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN=0
uint8 POWER_SUPPLY_TECHNOLOGY_NIMH=1
uint8 POWER_SUPPLY_TECHNOLOGY_LION=2
uint8 POWER_SUPPLY_TECHNOLOGY_LIPO=3
uint8 POWER_SUPPLY_TECHNOLOGY_LIFE=4
uint8 POWER_SUPPLY_TECHNOLOGY_NICD=5
uint8 POWER_SUPPLY_TECHNOLOGY_LIMN=6
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32 voltage
float32 current
float32 charge
float32 capacity
float32 design_capacity
float32 percentage
uint8 power_supply_status
uint8 power_supply_health
uint8 power_supply_technology
bool present
float32[] cell_voltage
string location
string serial_number
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/mavros/battery'
JSON Response:
{
voltage: Float,
current: Float,
remaining: Float
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/mavros/battery',
messageType: 'sensor_msgs/BatteryState'
Response:
{
voltage: Float,
current: Float,
remaining: Float
}
Example
rostopic echo /flytos/mavros/battery
Not Implemented
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
# Poll data
bat = drone.get_battery_status()
# Print the data
print bat.remaining, bat.current, bat.voltage
// Please refer to Roscpp documentation for sample subscriber nodes. http://wiki.ros.org/ROS/Tutorials/WritingPublisherSubscriber%28c%2B%2B%29
import rospy
from sensor_msgs.msg import BatteryState
# setup a subscriber and associate a callback function which will be called every time topic is updated.
topic_sub = rospy.Subscriber("/<namespace>/mavros/battery"), BatteryState, topic_callback)
# define the callback function which will print the values every time topic is updated
def topic_callback(data):
voltage = data.voltage
print voltage
# unsubscribe from a topic
topic_sub.unregister() # unregister topic subscription
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/mavros/battery",
success: function(data){
console.log(data);
}
});
var batteryData = new ROSLIB.Topic({
ros : ros,
name : '/<namespace>/mavros/battery',
messageType : 'sensor_msgs/BatteryState'
});
batteryData.subscribe(function(message) {
console.log(message.data);
});
Example response
header:
seq: 415
stamp:
secs: 1489486630
nsecs: 434288692
frame_id: ''
voltage: 65.5350036621
current: 0.00999999977648
charge: nan
capacity: nan
design_capacity: nan
percentage: -0.00999999977648
power_supply_status: 2
power_supply_health: 0
power_supply_technology: 3
present: True
cell_voltage: []
location: id0
serial_number: ''
Not Implemented
instance of class battery_status
instance of sensor_msgs.msg.BatteryState class
{
voltage: Float,
current: Float,
remaining: Float}
{
voltage: Float,
current: Float,
remaining: Float}
Description:
This API subscribes/polls battery status. Please check API usage section below before using API.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Response:
Parameter | Type | Description |
---|---|---|
voltage | float | total voltage, Volts |
current | float | instantaneous current consumption, Amperes |
charge | float | Charge |
capacity | float | capacity |
percentage | float | percentage left |
API usage information:
- This API provides voltage, current, remaining battery information.
ROS endpoint:
All the autopilot state / payload data in FlytOS is shared by ROS topics. Onboard topic subscribers in rospy / roscpp can subscribe to these topics. Take a look at roscpp and rospy API definition for response message structure.
- Type:
Ros Topic
- Name:
/<namespace>/mavros/battery
- Response Type:
sensor_msgs/BatteryState
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice. All RESTful APIs can poll the data. For telemetry mode (continuous data stream) use websocket APIs.
- URL:
GET http://<ip>/ros/<namespace>/mavros/battery
- JSON Response:
{ voltage: Float, current: Float, remaining: Float }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/mavros/battery
- messageType:
sensor_msgs/BatteryState
Get VFR HUD
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Topic Name: /<namespace>/mavros/vfr_hud
ROS-Topic Type: mavros_msgs/VFR_HUD
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32 airspeed
float32 groundspeed
int16 heading
float32 throttle
float32 altitude
float32 climb
Not Implemented
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.API.navigation
Function: get_vfr_hud()
Response: vfr_hud as described below.
class vfr_hud:
'''
Holds data for VFR HUD
'''
airspeed = 0.0
groundspeed = 0.0
heading = 0.0
throttle = 0.0
altitude = 0.0
climb = 0.0
This API supports single poll mode only.
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Topic
Name: /<namespace>/mavros/mavros_msgs/vfr_hud
Response structure: mavros_msgs/VFR_HUD
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32 airspeed
float32 groundspeed
int16 heading
float32 throttle
float32 altitude
float32 climb
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Topic
Name: /<namespace>/mavros/mavros_msgs/vfr_hud
Response structure: mavros_msgs/VFR_HUD
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32 airspeed
float32 groundspeed
int16 heading
float32 throttle
float32 altitude
float32 climb
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/mavros/vfr_hud'
JSON Response:
{ airspeed:Float,
groundspeed: Float,
heading: Integer,
throttle: Float,
altitude: Float,
climb: Float
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/mavros/vfr_hud',
messageType: 'mavros_msgs/VFR_HUD'
Response:
{ airspeed:Float,
groundspeed: Float,
heading: Integer,
throttle: Float,
altitude: Float,
climb: Float
}
Example
rostopic echo /flytos/mavros/mavros_msgs/vfr_hud
Not Implemented
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
# Poll data
vfr = drone.get_vfr_hud()
# Print the data
print vfr.throttle, vfr.groundspeed, vfr.airspeed, vfr.altitude, vfr.climb, vfr.heading
// Please refer to Roscpp documentation for sample subscriber nodes. http://wiki.ros.org/ROS/Tutorials/WritingPublisherSubscriber%28c%2B%2B%29
import rospy
from mavros_msgs.msgs import VFR_HUD
# setup a subscriber and associate a callback function which will be called every time topic is updated.
topic_sub = rospy.Subscriber("/<namespace>/mavros/vfr_hud"), VFR_HUD, topic_callback)
# define the callback function which will print the values every time topic is updated
def topic_callback(data):
airspeed = data.airspeed
print airspeed
# unsubscribe from a topic
topic_sub.unregister() # unregister topic subscription
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/mavros/vfr_hud",
success: function(data){
console.log(data);
}
});
var vfrHUDData = new ROSLIB.Topic({
ros : ros,
name : '/<namespace>/mavros/vfr_hud',
messageType : 'mavros_msgs/VFR_HUD'
});
vfrHUDData.subscribe(function(message) {
console.log(message.data);
});
Example response
header:
seq: 3664
stamp:
secs: 1489486597
nsecs: 915001340
frame_id: ''
airspeed: 0.0
groundspeed: 0.0
heading: 289
throttle: 0.0
altitude: 601.289001465
climb: -0.0
Not Implemented
instance of class vfr_hud
instance of mavros_msgs.msgs.VFR_HUD class
{
airspeed:Float,
groundspeed: Float,
heading: Integer,
throttle: Float,
altitude: Float,
climb: Float
}
{
airspeed:Float,
groundspeed: Float,
heading: Integer,
throttle: Float,
altitude: Float,
climb: Float
}
Description:
This API subscribes/polls VFR HUD data. Please check API usage section below before using API.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Response:
Parameter | Type | Description |
---|---|---|
airspeed | float | airspeed in m/s |
groundspeed | float | groundspeed in m/s |
heading | int16 | yaw angle in degrees (NED frame) |
throttle | float | throttle |
altitude | float | altitude |
climb | float | climb |
API usage information:
- airspeed data is the data from airspeed sensor.
ROS endpoint:
All the autopilot state/payload data in FlytOS is shared by ROS topics. Onboard topic subscribers in rospy/roscpp can subscribe to these topics. Take a look at roscpp and rospy API definition for response message structure.
- Type:
Ros Topic
- Name:
/<namespace>/mavros/vfr_hud
- Response Type:
mavros_msgs/VFR_HUD
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice. All RESTful APIs can poll the data. For telemetry mode (continuous data stream) use websocket APIs.
- URL:
GET http://<ip>/ros/<namespace>/mavros/vfr_hud
- JSON Response:
{ airspeed:Float, groundspeed: Float, heading: Integer, throttle: Float, altitude: Float, climb: Float }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/mavros/vfr_hud
- messageType:
mavros_msgs/VFR_HUD
Get RC Data
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Topic Name: /<namespace>/mavros/rc/in
ROS-Topic Type: mavros_msgs/RCIn
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
uint8 rssi
uint16[] channels
// CPP API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from cpp.
Function Definition: sysSubscribe(Navigation::rc_channels,rcChannelCb);
Arguments:
rc_channels: This argument selects RC channels topic to be subscribed
rcChannelCb: Callback function for the subscribed RC channel messages
Returns: RC channel info in ros mavros_msgs::RCInConstPtr structure
std_msgs/Header header
uint32 seq
time stamp
string frame_id
uint8 rssi
uint16[] channels
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.API.navigation
Function: get_rc_data()
Response: rc_data as described below.
class rc_data:
"""
Holds the input rc channel data
"""
rssi = 0
channels = []
This API supports single poll mode only.
// ROS services and topics are accessible from onboard scripts only.
ROS-Topic Name: /<namespace>/mavros/rc/in
ROS-Topic Type: mavros_msgs/RCIn
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
uint8 rssi
uint16[] channels
# ROS services and topics are accessible from onboard scripts only.
ROS-Topic Name: /<namespace>/mavros/rc/in
ROS-Topic Type: mavros_msgs/RCIn
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
uint8 rssi
uint16[] channels
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/mavros/rc/in'
JSON Response:
{
rssi: Int,
channels: Int[]
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/mavros/rc/in',
messageType: 'mavros_msgs/RCIn'
Response:
{
rssi: Int,
channels: Int[]
}
Example
rostopic echo /flytos/mavros/rc/in
#include <cpp_api/navigation_bridge.h>
Navigation nav;
mavros_msgs::RCIn rc_channel;
void rcChannelCb(void *_rc_channel)
{
rc_channel = * (mavros_msgs::RCIn*)(_rc_channel);
}
nav.sysSubscribe(Navigation::rc_channels,rcChannelCb);
std::cout << rc_channel << std::endl;
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
# Poll data
rc = drone.get_rc_data()
# Print the data
print rc.rssi, rc.channels
// Please refer to Roscpp documentation for sample subscriber nodes. http://wiki.ros.org/ROS/Tutorials/WritingPublisherSubscriber%28c%2B%2B%29
import rospy
from mavros_msgs.msgs import RCIn
# setup a subscriber and associate a callback function which will be called every time topic is updated.
topic_sub = rospy.Subscriber("/<namespace>/mavros/rc/in"), State, topic_callback)
# define the callback function which will print the values every time topic is updated
def topic_callback(data):
# print data from first 6 channels
print data.channels[:6]
# unsubscribe from a topic
topic_sub.unregister() # unregister topic subscription
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/mavros/rc/in",
success: function(data){
console.log(data);
}
});
var rcData = new ROSLIB.Topic({
ros : ros,
name : '/<namespace>/mavros/rc/in',
messageType : 'mavros_msgs/RCIn'
});
rcData.subscribe(function(message) {
console.log(message.data);
});
Example response
instance of mavros_msgs/RCIn
instance of mavros_msgs::RCIn
instance of class rc_data
success: True
[1001,999,1400,1234,1764,1900]
{
rssi: Int,
channels: Int[]
}
{
rssi: Int,
channels: Int[]
}
Description:
This API subscribes/polls the input rc channel data. Please see usage information section below before using the API.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Response:
Parameter | Type | Description |
---|---|---|
channels | Array of unit16 | Array of PWM data values for channels. |
API usage information:
- Channel mapping of the data depends on RC calibration.
ROS endpoint:
All the autopilot state / payload data in FlytOS is shared by ROS topics. Onboard topic subscribers in rospy / roscpp can subscribe to these topics. Take a look at roscpp and rospy API definition for response message structure.
- Type:
Ros Topic
- Name:
/<namespace>/mavros/rc/in
- Response Type:
mavros_msgs/RCIn
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice. All RESTful APIs can poll the data. For telemetry mode (continuous data stream) use websocket APIs.
- URL:
GET http://<ip>/ros/<namespace>/mavros/rc/in
- JSON Response:
{ rssi: Int, channels: Int[] }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/mavros/rc/in
- messageType:
mavros_msgs/RCIn
Get Distance Sensor
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Topic Name: /<namespace>/mavros/distance_sensor/lidarlite_pub
ROS-Topic Type: sensor_msgs/Range
Response structure:
uint8 ULTRASOUND=0
uint8 INFRARED=1
std_msgs/Header header
uint32 seq
time stamp
string frame_id
uint8 radiation_type
float32 field_of_view
float32 min_range
float32 max_range
float32 range
Not Implemented
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.API.navigation
Function: get_distance_sensor()
Response: dist_sensor as described below.
class dist_sensor:
"""
Holds distance sensor data
"""
radiation_type = 0
field_of_view = 0.0
min_range = 0.0
max_range = 0.0
range = 0.0
This API supports single poll mode only.
// ROS services and topics are accessible from onboard scripts only.
ROS-Topic Name: /<namespace>/mavros/distance_sensor/lidarlite_pub
ROS-Topic Type: sensor_msgs/Range
Response structure:
uint8 ULTRASOUND=0
uint8 INFRARED=1
std_msgs/Header header
uint32 seq
time stamp
string frame_id
uint8 radiation_type
float32 field_of_view
float32 min_range
float32 max_range
float32 range
# ROS services and topics are accessible from onboard scripts only.
ROS-Topic Name: /<namespace>/mavros/distance_sensor/lidarlite_pub
ROS-Topic Type: sensor_msgs/Range
Response structure:
uint8 ULTRASOUND=0
uint8 INFRARED=1
std_msgs/Header header
uint32 seq
time stamp
string frame_id
uint8 radiation_type
float32 field_of_view
float32 min_range
float32 max_range
float32 range
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/mavros/distance_sensor/lidarlite_pub'
JSON Response:
{
radiation_type: Int,
field_of_view: Float,
min_range: Float,
max_range: Float,
range: Float
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/mavros/distance_sensor/lidarlite_pub',
messageType: 'sensor_msgs/Range'
Response:
{
radiation_type: Int,
field_of_view: Float,
min_range: Float,
max_range: Float,
range: Float
}
Example
rostopic echo /flytos/mavros/distance_sensor/lidarlite_pub
Not Implemented
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
# Poll data
dist = drone.get_distance_sensor()
# Print the data
print dist.range, dist.max_range, dist.min_range, dist.field_of_view, dist.radiation_type
// Please refer to Roscpp documentation for sample subscriber nodes. http://wiki.ros.org/ROS/Tutorials/WritingPublisherSubscriber%28c%2B%2B%29
import rospy
from sensor_msgs.msgs import Range
# setup a subscriber and associate a callback function which will be called every time topic is updated.
topic_sub = rospy.Subscriber("/<namespace>/mavros/distance_sensor/lidarlite_pub"), Range, topic_callback)
# define the callback function which will print the values every time topic is updated
def topic_callback(data):
dist = data.range
print dist
# unsubscribe from a topic
topic_sub.unregister() # unregister topic subscription
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/mavros/distance_sensor/lidarlite_pub",
success: function(data){
console.log(data);
}
});
var distanceData = new ROSLIB.Topic({
ros : ros,
name : '/<namespace>/mavros/distance_sensor/lidarlite_pub',
messageType : 'sensor_msgs/Range'
});
distanceData.subscribe(function(message) {
console.log(message.data);
});
Example response
instance of sensor_msgs/Range
Not Implemented
instance of class dist_sensor
instance of sensor_msgs.msgs.Range object
{
radiation_type: Int,
field_of_view: Float,
min_range: Float,
max_range: Float,
range: Float
}
{
radiation_type: Int,
field_of_view: Float,
min_range: Float,
max_range: Float,
range: Float
}
Description:
This API subscribes/polls distance sensor data. Check API usage section below before using API.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Response:
Parameter | Type | Description |
---|---|---|
range | float | distance to ground in meters |
API usage information:
- This topic provides data from Lidarlite rangefinder, ultrasonic SONAR sensor, etc.
- This API will work on any px4 supported hardware.
- If you are using FlytPOD then check hardware and wiring sections in docs for wiring info.
- If you are using anything else than FlytPOD then refer to respective autopilot documentation for wiring info.
ROS endpoint:
All the autopilot state / payload data in FlytOS is shared by ROS topics. Onboard topic subscribers in rospy / roscpp can subscribe to these topics. Take a look at roscpp and rospy API definition for response message structure.
- Type:
Ros Topic
- Name:
/<namespace>/mavros/distance_sensor/lidarlite_pub
- Response Type:
sensor_msgs/Range
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice. All RESTful APIs can poll the data. For telemetry mode (continuous data stream) use websocket APIs.
- URL:
GET http://<ip>/ros/<namespace>/mavros/distance_sensor/lidarlite_pub
- JSON Response:
{ radiation_type: Int, field_of_view: Float, min_range: Float, max_range: Float, range: Float }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/mavros/distance_sensor/lidarlite_pub
- messageType:
sensor_msgs/Range
Get Vehicle State
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Topic Name: /<namespace>/flyt/state
ROS-Topic Type: mavros_msgs/State
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
bool connected
bool armed
bool guided
string mode
uint8 mav_type
uint8 mav_autopilot
uint8 mav_sys_status
// CPP API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from cpp.
Function Definition: sysSubscribe(Navigation::vehicle_state,vehicleModeCb);
Arguments:
vehicle_state: This argument selects vehicle state topic to be subscribed
vehicleModeCb: Callback function for the subscribed vehicle state messages
Returns: Vehicle state in ros mavros_msgs::State message structure
std_msgs/Header header
uint32 seq
time stamp
string frame_id
bool connected
bool armed
bool guided
string mode
uint8 mav_type
uint8 mav_autopilot
uint8 mav_sys_status
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
# Python API for vehicle state is split into three APIs
# Get full vehicle state data
Class: flyt_python.API.navigation
Function: get_vehicle_state()
Response: vehicle_state as described below.
class vehicle_state:
"""
Holds vehicle state data
"""
connected = False
armed = False
guided = False
mode = 'String'
mav_type = 0
mav_autopilot = 0
mav_sys_status = 0
This API supports single poll mode only.
# Check arm status
Class: flyt_python.api.navigation
Function Definition: is_armed()
Arguments: None
return: Boolean
# Check vehicle mode
Class: flyt_python.api.navigation
Function Definition: get_vehicle_mode()
Arguments: None
return: string
// ROS services and topics are accessible from onboard scripts only.
ROS-Topic Name: /<namespace>/flyt/state
ROS-Topic Type: mavros_msgs/State
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
bool connected
bool armed
bool guided
string mode
uint8 mav_type
uint8 mav_autopilot
uint8 mav_sys_status
# ROS services and topics are accessible from onboard scripts only.
ROS-Topic Name: /<namespace>/flyt/state
ROS-Topic Type: mavros_msgs/State
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
bool connected
bool armed
bool guided
string mode
uint8 mav_type
uint8 mav_autopilot
uint8 mav_sys_status
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/flyt/state'
JSON Response:
{ connected: Boolean,
armed: Boolean,
guided: Boolean,
mode: String,
mav_type: Int,
mav_autopilot: Int,
mav_sys_status: Int
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/flyt/state',
messageType: 'mavros_msgs/State'
Response:
{ connected: Boolean,
armed: Boolean,
guided: Boolean,
mode: String,
mav_type: Int,
mav_autopilot: Int,
mav_sys_status: Int
}
Example
rostopic echo /flytos/flyt/state
#include <cpp_api/navigation_bridge.h>
Navigation nav;
mavros_msgs::State vehicle_state;
void attitudeQuatCb(void *_vehicle_state)
{
vehicle_state = * (mavros_msgs::State*)(_vehicle_state);
}
nav.sysSubscribe(Navigation::vehicle_state,vehicleModeCb);
std::cout << vehicle_state << std::endl;
# create flyt_python navigation class instance
from flyt_python import api
drone = api.navigation()
time.sleep(3.0)
# Poll data
st = drone.get_vehicle_state()
# Print the data
print st.connected, st.armed, st.guided, st.mode, st.mav_type, st.mav_autopilot, st.mav_sys_status
# get arm status
print drone.is_armed()
print drone.get_vehicle_mode()
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
import rospy
from mavros_msgs.msgs import State
# setup a subscriber and associate a callback function which will be called every time topic is updated.
topic_sub = rospy.Subscriber("/<namespace>/flyt/state"), State, topic_callback)
# define the callback function which will print the values every time topic is updated
def topic_callback(data):
mode, is_armed = data.mode, data.armed
print mode, is_armed
# unsubscribe from a topic
topic_sub.unregister() # unregister topic subscription
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/flyt/state",
success: function(data){
console.log(data);
}
});
var stateData = new ROSLIB.Topic({
ros : ros,
name : '/<namespace>/flyt/state',
messageType : 'mavros_msgs/State'
});
stateData.subscribe(function(message) {
console.log(message.data);
});
Example response
header:
seq: 1666
stamp:
secs: 1489487905
nsecs: 864919940
frame_id: ''
connected: True
armed: False
guided: False
mode: RC|MANUAL
mav_type: 2
mav_autopilot: 12
mav_sys_status: 0
Instance of mavros_msgs::State class
instance of class vehicle_state
True
MANUAL
True MANUAL
{
connected: Boolean,
armed: Boolean,
guided: Boolean,
mode: String,
mav_type: Int,
mav_autopilot: Int,
mav_sys_status: Int
}
{
connected: Boolean,
armed: Boolean,
guided: Boolean,
mode: String,
mav_type: Int,
mav_autopilot: Int,
mav_sys_status: Int
}
Description:
This API subscribes/polls the vehicle state data. Check usage information section below before using the API.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Response:
Parameter | Type | Description |
---|---|---|
mode | string | autopilot flight mode e.g. MANUAL, APICTL |
armed | boolean | Vehicle arm status. Armed if True and disarmed if False. |
API usage information:
- This API provides mode and arm status.
- All navigation API’s work only in Offboard / APICTL mode. So checking the mode before firing mission critical commands is advised.
- This API only allows to read the mode and arm status.
ROS endpoint:
All the autopilot state/payload data in FlytOS is shared by ROS topics. Onboard topic subscribers in rospy / roscpp can subscribe to these topics. Take a look at roscpp and rospy API definition for response message structure.
- Type:
Ros Topic
- Name:
/<namespace>/flyt/state
- Response Type:
mavros_msgs/State
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice. All RESTful APIs can poll the data. For telemetry mode (continuous data stream) use websocket APIs.
- URL:
GET http://<ip>/ros/<namespace>/flyt/state
- JSON Response:
{ connected: Boolean, armed: Boolean, guided: Boolean, mode: String, mav_type: Int, mav_autopilot: Int, mav_sys_status: Int }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/flyt/state
- messageType:
mavros_msgs/State
Payload APIs
Get ADC data
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Topic Name: /<namespace>/mavros/payload_adc
ROS-Topic Type: mavros_msgs/PayloadADC
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32[2] adc_voltage
uint8 adc_updated
// CPP API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from cpp.
Not Implemented
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from python.
Class: flyt_python.API.navigation
Function: get_adc_data()
Response: adc_data as described below.
class adc_data:
"""
Holds ADC data
"""
adc_voltage = []
adc_updated = 0
This API supports single poll mode only.
// ROS services and topics are accessible from onboard scripts only.
ROS-Topic Name: /<namespace>/mavros/payload_adc
ROS-Topic Type: mavros_msgs/PayloadADC
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32[2] adc_voltage
uint8 adc_updated
# ROS services and topics are accessible from onboard scripts only.
ROS-Topic Name: /<namespace>/mavros/payload_adc
ROS-Topic Type: mavros_msgs/PayloadADC
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32[2] adc_voltage
uint8 adc_updated
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/mavros/payload_adc'
JSON Response:
{
adc_voltage: Float[2],
adc_updated: Int
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/mavros/payload_adc',
messageType: 'mavros_msgs/PayloadADC'
Response:
{
adc_voltage: Float[2],
adc_updated: Int
}
Example
rostopic echo /flytos/mavros/payload_adc
#sends (x,y,z)=(1.0,3.5,-5.0)(m), yaw=0.12rad, relative=false, async=false, yaw_valid=true, body_frame=false
#default value of tolerance=1.0m if left at 0
Not Implemented
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
# Poll data
adc = drone.get_adc_data()
# Print the data
print adc.adc_voltage, adc.adc_updated
#include <core_api/PositionSet.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::PositionSet>("/<namespace>/navigation/position_set");
core_api::PositionSet srv;
srv.request.twist.twist.angular.z = 0.12;
srv.request.twist.twist.linear.x = 1.0;
srv.request.twist.twist.linear.y = 3.5;
srv.request.twist.twist.linear.z = -5.0;
srv.request.tolerance = 5.0;
srv.request.async = false;
srv.request.yaw_valid = true;
srv.request.relative = false;
srv.request.body_frame = false;
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
//sends (x,y,z)=(1.0,3.5,-5.0)(m), yaw=0.12rad, tolerance=5.0m, relative=false, async=false, yaw_valid=true, body_frame=false
import rospy
from mavros_msgs.msgs import PayloadADC
# setup a subscriber and associate a callback function which will be called every time topic is updated.
topic_sub = rospy.Subscriber("/<namespace>/mavros/payload_adc"), PayloadADC, topic_callback)
# define the callback function which will print the values every time topic is updated
def topic_callback(data):
adc1,adc2 = data.adc_voltage[0],data.adc_voltage[1]
print adc1, adc2
# unsubscribe from a topic
topic_sub.unregister() # unregister topic subscription
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/mavros/payload_adc",
success: function(data){
console.log(data);
}
});
var adcData = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/mavros/payload_adc',
messageType : 'mavros_msgs/PayloadADC'
});
var request = new ROSLIB.ServiceRequest({});
adcData.subscribe(request, function(result) {
console.log(result.data);
});
Example response
adc_voltage: Float[2],
adc_updated: Int
Not Implemented
instance of class adc_data
success: True
instance of mavros_msgs.msgs.PayloadADC object
{
adc_voltage: Float[2],
adc_updated: Int
}
{
adc_voltage: Float[2],
adc_updated: Int
}
Description:
This API subscribes/polls the ADC payload data. This API is limited to FlytPOD only. Check usage information section below before using the API.
Parameters:
Following parameters are applicable for onboard cpp and python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Response:
Parameter | Type | Description |
---|---|---|
adc_voltage | array (2*1) of floats | array of adc voltage readings in volts. |
adc_updated | uint8 | Bitmask indicating updated channel. possible values: [0,1,2,3] |
API usage information:
- This API works only on FlytPOD.
- There are two ADC channels available on back IO panel of FlytPOD. Refer to hardware connections section in FlytPOD documentation for more info on wiring.
- ADC channel operational input voltage range is 0 to 3.3 V.
ROS endpoint:
All the autopilot state/payload data in FlytOS is shared by ROS topics. Onboard topic subscribers in rospy/roscpp can subscribe to these topics. Take a look at roscpp and rospy API definition for response message structure.
- Type:
Ros Topic
- Name:
/<namespace>/mavros/payload_adc
- Response Type:
mavros_msgs/PayloadADC
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice. All RESTful APIs can poll the data. For telemetry mode (continuous data stream) use websocket APIs.
- URL:
GET http://<ip>/ros/<namespace>/mavros/payload_adc
- JSON Response:
{ adc_voltage: Float[2], adc_updated: Int }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/mavros/payload_adc
- messageType:
mavros_msgs/PayloadADC
Gimbal Control
Definition
# API call described below requires shell access, either login to the device using desktop or use ssh for remote login.
ROS-Service Name: /<namespace>/payload/gimbal_set
ROS-Service Type: core_api/GimbalSet, below is its description
#Request : expects gimbal attitude setpoint in radians via roll, pitch, yaw in NED Frame
#Response : return success=true if command is successfully sent
float64 roll
float64 pitch
float64 yaw
---
bool success
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Not Implemented
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: gimbal_control( roll, pitch, yaw)
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/payload/gimbal_set
call srv:
:float64 roll
:float64 pitch
:float64 yaw
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Type: Ros Service
Name: /<namespace>/payload/gimbal_set
call srv:
:float64 roll
:float64 pitch
:float64 yaw
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/payload/gimbal_set'
JSON Request:
{
roll: Float,
pitch: Float,
yaw: Float
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/payload/gimbal_set',
serviceType: 'core_api/GimbalSet'
Request:
{
roll: Float,
pitch: Float,
yaw: Float
}
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /<namespace>/payload/gimbal_set "roll: 0.0
pitch:0.5
yaw:-0.2"
#sends (roll,pitch,yaw)=(0,0.5,-0.2)(rad)
Not Implemented
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#send gimbal attitude set
drone.gimbal_control(2.2,1.4, 1.5)
#include <core_api/GimbalSet.h>
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<core_api::GimbalSet>("/<namespace>/payload/gimbal_set");
core_api::GimbalSet srv;
srv.request.roll = 0.0;
srv.request.pitch = 0.5;
srv.request.yaw = -0.2;
client.call(srv);
bool success = srv.response.success;
std::string message = srv.response.message;
import rospy
from core_api.srv import *
def setpoint_gimbal(roll, pitch, yaw):
rospy.wait_for_service('<namespace>/payload/gimbal_set')
try:
handle = rospy.ServiceProxy('<namespace>/payload/gimbal_set', GimbalSet)
resp = handle(roll, pitch, yaw)
return resp
except rospy.ServiceException, e:
rospy.logerr("gimbal_set service call failed %s", e)```
var msgdata={};
msgdata["roll"]=0.0;
msgdata["pitch"]=0.5;
msgdata["yaw"]=-0.2;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/payload/gimbal_set",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var gimbalSet = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/payload/gimbal_set',
serviceType : 'core_api/GimbalSet'
});
var request = new ROSLIB.ServiceRequest({
roll: 0.0,
roll: 0.5,
roll: -0.2
});
gimbalSet.callService(request, function(result) {
console.log('Result for service call on '
+ gimbalSet.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
Not Implemented
{'message': '[INFO] Vehicle accepted gimbal set call', 'success': True}
message (string): Contains error message
success (bool): true if action successful
success: True
Success: True
{
success:True
}
{
success:True
}
Description:
This API sends gimbal attitude setpoint command to the autopilot via MAVLink and outputs pwm signals on gimbal-dedicated port of FlytPOD/Pixhawk.
Pre-requisites:
For this API to work, autopilot must fulfill some pre-requisites first:
For FlytPOD/PRO users:
- Autopilot MUST be in ready-to-arm state. Typically it would be reflected by RGB led patterns marked by either blue-breathing or green-breathing. For more information about autopilot RGBled patterns refer to this link.
- Make sure the parameter: MNT_MODE_IN is set to 3.
For PX4 users using Pixhawk:
- Autopilot MUST be in ready-to-arm state. Typically it would be reflected by RGBled patterns marked by either blue-breathing or green-breathing. For more information about autopilot RGBled patterns refer to this link.
- Make sure the parameter: MNT_MODE_IN is set to 3.
- For more information refer to this guide by PX4.
For APM users using Pixhawk: * Refer this guide by APM.
Parameters:
Following parameters are applicable for onboard C++ and Python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
roll | float | roll command to gimbal in radians |
pitch | float | pitch command to gimbal in radians |
yaw | float | yaw command to gimbal in radians |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
ROS endpoint:
Payload APIs in FlytOS are derived from / wrapped around the core services available in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/payload/gimbal_set
- Service Type:
GimbalSet
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/payload/gimbal_set
- JSON Request:
{ roll: Float, pitch: Float, yaw: Float }
- JSON Response:
{ success: Boolean, message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/payload/gimbal_set
- serviceType:
core_api/GimbalSet
Obstacle Detection
Definition
# API call described below requires shell access, either login to the device using desktop or use ssh for remote login.
ROS-Topic Name: /<namespace>/dji_msdk/obstacle_distance
ROS-Topic Type: core_api/ObstacleData, below is its description
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32[] front
float32[] back
uint8[] front_warning_level
uint8[] back_warning_level
bool on_hold
bool is_enabled
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
// Not Implemented
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
# Not Implemented
// ROS services and topics are accessible from onboard scripts only.
ROS-Topic Name: /<namespace>/dji_msdk/obstacle_distance
ROS-Topic Type: core_api/ObstacleData, below is its description
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32[] front
float32[] back
uint8[] front_warning_level
uint8[] back_warning_level
bool on_hold
bool is_enabled
# ROS services and topics are accessible from onboard scripts only.
ROS-Topic Name: /<namespace>/dji_msdk/obstacle_distance
ROS-Topic Type: core_api/ObstacleData, below is its description
Response structure:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32[] front
float32[] back
uint8[] front_warning_level
uint8[] back_warning_level
bool on_hold
bool is_enabled
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/dji_msdk/obstacle_distance'
JSON Response:
{
front: FloatArray,
back: FloatArray,
front_warning_level: IntArray,
back_warning_level: IntArray,
on_hold: Bool,
is_enabled: Bool
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/dji_msdk/obstacle_distance',
serviceType: 'core_api/ObstacleData'
Response:
{
front: FloatArray,
back: FloatArray,
front_warning_level: IntArray,
back_warning_level: IntArray,
on_hold: Bool,
is_enabled: Bool
}
Example
Not Implemented
Not Implemented
Not Implemented
Not Implemented
Not Implemented
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/dji_msdk/obstacle_distance",
success: function(data) {
console.log(data);
}
});
var obsData = new ROSLIB.Topic({
ros : ros,
name : '/<namespace>/dji_msdk/obstacle_distance',
messageType : 'core_api/ObstacleData',
throttle_rate: 200
});
obsData.subscribe(function(message) {
console.log(message);
});
Example response
Not Implemented
Not Implemented
Not Implemented
Not Implemented
Not Implemented
Not Implemented
front: [16.43000030517578, 14.010000228881836, 0.8700000047683716, 0.8700000047683716]
back: [0.8700000047683716, 0.8700000047683716, 0.8700000047683716, 15.569999694824219]
front_warning_level: [0, 0, 5, 5],
back_warning_level: [5, 5, 5, 0],
on_hold: False
is_enabled: False
Description:
This API publishes detected obstacle data of a supported DJI drone.
Parameters:
Following parameters are applicable for onboard C++ and Python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
front | floatArray | array of detected obstacle distance (in m) for every quadrant of front sensor from left to right |
back | floatArray | array of detected obstacle distance (in m) for every quadrant of back sensor from left to right |
front_warning_level | intArray | array of warning levels for every quadrant of front sensor from left to right. Values in range (0 - 5) or 15. 0 being farthest and 5 being closest. If the sensor data is invalid, this value will be 15. |
back_warning_level | intArray | array of detected obstacle distance (in m) for every quadrant of back sensor from left to right |
on_hold | bool | stores state if autopilot has engaged obstacle avoidance |
is_enabled | bool | stores state if collision avoidance is enabled or not |
ROS endpoint:
Payload APIs in FlytOS are derived from / wrapped around the core services available in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/dji_msdk/obstacle_distance
- Service Type:
core_api/ObstacleData
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/dji_msdk/obstacle_distance
- serviceType:
core_api/ObstacleData
Collision Avoidance
Definition
# API call described below requires shell access, either login to the device using desktop or use ssh for remote login.
ROS-Service Name: /<namespace>/payload/collision_avoidance_configure
ROS-Service Type: core_api/CollisionAvoidanceConfigure, below is its description
#Request : expects enable_avoidance to enable/disable collision avoidance
#Response : return success=true if command is successfully sent
bool enable_avoidance
---
bool success
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Not Implemented
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Not Implemented
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/payload/collision_avoidance_configure
call srv:
:bool enable_avoidance
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/payload/collision_avoidance_configure
call srv:
:bool enable_avoidance
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/payload/collision_avoidance_configure'
JSON Request:
{
enable_avoidance: Boolean
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/payload/collision_avoidance_configure',
serviceType: 'core_api/CollisionAvoidanceConfigure'
Request:
{
enable_avoidance: Boolean
}
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /<namespace>/payload/collision_avoidance_configure "enable_avoidance: false"
Not Implemented
Not Implemented
Not Implemented
Not Implemented
var msgdata={};
msgdata["enable_avoidance"]=true;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/payload/collision_avoidance_configure",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var collision_avoidance_configure = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/payload/collision_avoidance_configure',
serviceType : 'core_api/CollisionAvoidanceConfigure'
});
var request = new ROSLIB.ServiceRequest({
enable_avoidance: true
});
collision_avoidance_configure.callService(request, function(result) {
console.log('Result for service call on '
+ gimbalSet.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
Not Implemented
Not Implemented
Not Implemented
Not Implemented
{
success:True
}
{
success:True
}
Description:
This API enables/disables collision avoidance system of the DJI drone.
Parameters:
Following parameters are applicable for onboard C++ and Python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
enable_avoidance | boolean | set to True to enable collision avoidance |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
ROS endpoint:
Payload APIs in FlytOS are derived from / wrapped around the core services available in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/payload/collision_avoidance_configure
- Service Type:
core_api/CollisionAvoidanceConfigure
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/payload/collision_avoidance_configure
- JSON Request:
{ enable_avoidance: Boolean }
- JSON Response:
{ success: Boolean, message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/payload/collision_avoidance_configure
- serviceType:
core_api/CollisionAvoidanceConfigure
Vehicle Setup APIs
Actuator Testing
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/setup/actuator_testing
ROS-Service Type: core_api/ActuatorTesting, below is its description
#request
uint8 actuator_id
float32 time_s
#response
bool success
string message
//Not Implemented
#Not Implemented
//Not Recommended
#Not Recommended
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/setup/actuator_testing'
JSON Request:
{
actuator_id: Int,
time_s: Float
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/setup/actuator_testing',
serviceType: 'core_api/ActuatorTesting'
Request:
{
actuator_id: Int,
time_s: Float
}
Response:
{
success: Boolean,
message: String
}
Example
# Refer to rosservice command line API documentation for sample service calls. http://wiki.ros.org/rosservice
//Not Implemented
# Not Implemented
//Not Recommended
# Not Recommended
var msgdata={};
msgdata["actuator_id"]=2;
msgdata["time_s"]=4.00;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/setup/actuator_testing",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var actuatorTesting = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/setup/actuator_testing',
serviceType : 'core_api/ActuatorTesting'
});
var request = new ROSLIB.ServiceRequest({
actuator_id: 2,
time_s: 4.00
});
actuatorTesting.callService(request, function(result) {
console.log('Result for service call on '
+ actuatorTesting.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
//Not Implemented
# Not Implemented
//Not Recommended
# Not Recommended
{
success:True
}
{
success:True
}
Description:
This API allows for testing an actuator by providing actuator ID and time to rotate as parameters. If the corresponding actuator rotates on execution of the API correctly for the defined time then the motors are correctly connected.
Parameters:
Following parameters are applicable for RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
actuator_id | int | Decide which actuator to trigger. |
time_s | float | Time in seconds to rotate the actuator |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
- Note: Make sure to check the direction of rotation while you trigger this API for correct response from the particular actuator.
ROS endpoint:
APIs in FlytOS are derived from / wrapped around the core services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/setup/actuator_testing
- Service Type:
ActuatorTesting
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/setup/actuator_testing
- JSON Request:
{ actuator_id: Int, time_s: Float }
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/setup/actuator_testing
- serviceType:
core_api/ActuatorTesting
ESC Calibration
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/setup/esc_calibration
ROS-Service Type: core_api/EscCalibration, below is its description
#request
int8 CALIBRATION_STATE_SET_PWM_MAX = 1
int8 CALIBRATION_STATE_SET_PWM_MIN = 2
int8 CALIBRATION_STATE_CANCEL = 3
float32 pwm_min
float32 pwm_max
int8 num_of_actuators
int8 calibration_state
#response
bool success
string message
//Not Implemented
#Not Implemented
//Not Recommended
#Not Recommended
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/setup/esc_calibration'
JSON Request:
{
pwm_min: Float,
pwm_max: Float,
num_of_actuators: Int,
calibration_state: Int
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/setup/esc_calibration',
serviceType: 'core_api/EscCalibration'
Request:
{
pwm_min: Float,
pwm_max: Float,
num_of_actuators: Int,
calibration_state: Int
}
Response:
{
success: Boolean,
message: String
}
Example
# Refer to rosservice command line API documentation for sample service calls. http://wiki.ros.org/rosservice
//Not Implemented
#Not Implemented
//Not Recommended
#Not Recommended
var msgdata={};
msgdata["pwm_min"]=1000.00;
msgdata["pwm_max"]=2000.00;
msgdata["num_of_actuators"]=4;
msgdata["calibration_state"]=2;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/setup/esc_calibration",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var escCalibration = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/setup/esc_calibration',
serviceType : 'core_api/EscCalibration'
});
var request = new ROSLIB.ServiceRequest({
pwm_min: 1000.00,
pwm_max: 2000.00,
num_of_actuators: 4,
calibration_state: 2
});
escCalibration.callService(request, function(result) {
console.log('Result for service call on '
+ escCalibration.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
//Not Implemented
#Not Implemented
//Not Recommended
#Not Recommended
{
success:True
}
{
success:True
}
Description:
This API helps calibrate ESCs.
Parameters:
Following parameters are applicable in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
pwm_min | float | Min PWM value to be expected |
pwm_max | float | Max PWM value to be expected |
num_of_actuators | Int | Number of actuator in the frame. |
calibration_state | Int | 1/2/3. |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
ROS endpoint:
APIs in FlytOS are derived from / wrapped around the core services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/setup/esc_calibration
- Service Type:
EscCalibration
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/\<namespace\>/setup/esc_calibration
- JSON Request:
{ pwm_min: Float, pwm_max: Float, num_of_actuators: Int, calibration_state: Int }
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/setup/esc_calibration
- serviceType: ‘core_api/EscCalibration’
Module Calibration
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
Type: Ros Service
Name: /<namespace>/setup/module_calibration
MsgType: core_api/ModuleCalibration
#request
uint8 STOP = 0
uint8 ACCELEROMETER = 1
uint8 GYROSCOPE = 2
uint8 MAGNETOMETER = 3
uint8 RC = 4
uint8 RC_TRIM = 5
uint8 RC_STOP = 6
uint8 LEVEL = 7
uint8 AIRSPEED = 8
int8 module_calibrate
#response
bool success
string message
//Not Implemented
#Not Implemented
//Not Recommended
#Not Recommended
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/setup/module_calibration'
JSON Request:
{
module_calibrate: Int
}
JSON Response:
{
success: Boolean,
message: String
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/setup/module_calibration',
serviceType: 'core_api/ModuleCalibration'
Request:
{
module_calibrate: Int
}
Response:
{
success: Boolean,
message: String
}
Example
# Refer to rosservice command line API documentation for sample service calls. http://wiki.ros.org/rosservice
//Not Implemented
#Not Implemented
//Not Recommended
#Not Recommended
var msgdata={};
msgdata["module_calibrate"]=2;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/setup/module_calibration",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var moduleCalibration = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/setup/module_calibration',
serviceType : 'core_api/ModuleCalibration'
});
var request = new ROSLIB.ServiceRequest({
module_calibrate: Int
});
moduleCalibration.callService(request, function(result) {
console.log('Result for service call on '
+ moduleCalibration.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: True
//Not Implemented
#Not Implemented
//Not Recommended
#Not Recommended
{
success:True
}
{
success:True
}
Description:
This API helps calibrate accelerometer, magnetometer, gyroscope, level and RC.
Parameters:
Following parameters are applicable in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
module_calibrate | int | module to calibrate. 1: accel 2: gyro 3: mag 4: radio 7: level |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
ROS endpoint:
APIs in FlytOS are derived from / wrapped around the core services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/setup/module_calibration
- Service Type:
ModuleCalibration
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/setup/module_calibration
- JSON Request:
{ module_calibrate: Int }
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/setup/module_calibration
- serviceType:
core_api/ModuleCalibration
Parameter APIs
Parameter Set
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/param/param_set
ROS-Service Type: core_api/ParamSet, below is its description
#Request : Info of parameter to be set
core_api/ParamInfo param_info
#Response : success=true if command is successful.
bool success
#Response : error message, if any
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: bool Param::param_set(std::string param_id, std::string param_value)
Arguments:
param_id: ID of param to be set
param_value: Value of param to be set
Returns: returns 0 if the command is successful
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: param_set(param_id, param_value)
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_set
call srv:
:core_api/ParamInfo param_info
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_set
call srv:
:core_api/ParamInfo param_info
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/param/param_set'
JSON Request:
{ param_info:{
param_id: String,
param_value: String
}}
JSON Response:
{ success: Boolean,
message: String, }
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/param/param_set',
serviceType: 'core_api/ParamSet'
Request:
{ param_info:{
param_id: String,
param_value: String }}
Response:
{
success: Boolean,
message: String
}
Example
rosservice call /flytos/param/param_set "param_info:
param_id: ''
param_value: ''"
#include <cpp_api/param_bridge.h>
Param param;
std::string param_id = "RTL_ALT";
std::string param_value = "5";
param.param_set(param_id, param_value);
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#Set parameter
drone.param_set('walk', 'on')
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
var msgdata={};msgdata["param_info"]={};
msgdata.param_info["param_id"]="RTL_ALT";
msgdata.param_info["param_value"]="5.0";
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/param/param_set",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var paramSet = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/param/param_set',
serviceType : 'core_api/ParamSet'
});
var request = new ROSLIB.ServiceRequest({
param_info:{
param_id: “RTL_ALT”,
param_value: “5.0”
});
paramSet.callService(request, function(result) {
console.log('Result for service call on '
+ paramSet.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
bool : true if action successful
{
success:True
}
{
success:True
}
Description:
This API sets the value of a desired parameter
Parameters:
Following parameters are applicable in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
param_id | string | Name of the parameter to be updated |
param_value | string | Value of the parameter to be set. |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
ROS endpoint:
APIs in FlytOS are derived from / wrapped around the core services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/param/param_set
- Service Type:
ParamSet
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/param/param_set
- JSON Request:
{ param_info:{ param_id: [String], param_value: [String] } }
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/param/param_set
- serviceType:
core_api/ParamSet
Parameter Get All
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/param/param_get_all
ROS-Service Type: core_api/ParamGetAll, below is its description
#Request : fresh pull true or false
bool fresh_pull
#Response: ParamInfo list of all parameters
core_api/ParamInfo[] param_list
#Response : success=true if command is successful.
bool success
#Response : error message, if any
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: bool Param::param_get_all(std::vector<core_api::ParamInfo> ¶m_list, bool fresh_pull)
Arguments:
fresh_pull: Whether to fresh pull from autopilot or not
param_list: Variable to store parameter list
Returns:
returns parameter info list in param_list
returns 0 if the command is successful
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: param_get_all()
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_get_all
call srv:
:bool fresh_pull
response srv:
:core_api/ParamInfo[] param_list
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_get_all
call srv:
:bool fresh_pull
response srv:
:core_api/ParamInfo[] param_list
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/param/param_get_all'
JSON Response:
{ success: Boolean,
message: String,
param_list: [{ param_id: [String],
param_value: [String]},{},{},...]
}
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/param/param_get_all',
serviceType: 'core_api/ParamGetAll'
Response:
{ success: Boolean,
message: String,
param_list: [{ param_id: [String],
param_value: [String]},{},{},...] }
Example
rosservice call /flytos/param/param_get_all "fresh_pull: false"
#include <cpp_api/param_bridge.h>
Param param;
bool fresh_pull = false;
core_api/ParamInfo[] param_list;
param.param_get_all(param_list, fresh_pull);
std::cout << "Parameter list: " << param_list << std::endl;
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#Get all parameter
drone.param_get_all()
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
$.ajax({
type: "GET",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/param/param_get_all",
success: function(data){
console.log(data.param_list);
}
});
var paramGetAll = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/param/param_get_all',
serviceType : 'core_api/ParamGetAll'
});
var request = new ROSLIB.ServiceRequest({});
paramGetAll.callService(request, function(result) {
console.log('Result for service call on '
+ ParamGetAll.name
+ ': '
+ result.param_list);
});
Example response
success:True,
param_list:[{},{},{},....]
Function returns 0
param_list is populated with all the received parameters
{'param_list': [{'param_value': '0.200000', 'param_id': 'ATT_VIBE_THRESH'}, {'param_value': '15.391030', 'param_id': 'BAT_A_PER_V'}], 'message': 'Received 2 parameters', 'success': True}
param_list (list): list of dictionary, each dictionary consists of param_value and param_id
message (String): Contains error/success message
success (bool): true if action successful
{
success:True,
param_list:[{},{},{},....]
}
{
success:True,
param_list:[{},{},{},....]
}
Description:
This API gets all the parameters available in FlytOS with their values.
Parameters:
Following parameters are applicable in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
param_id | string | Name of the parameter |
param_value | string | value of the parameter |
ROS endpoint:
APIs in FlytOS are derived from/wrapped around the core services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/param/param_get_all
- Service Type:
ParamGetAll
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/param/param_get_all
- JSON Response:
{ success: Boolean, message: String, param_list:[{ param_id: String, param_value: String },{},{},....] }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/param/param_get_all
- serviceType:
core_api/ParamGetAll
Parameter Get
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/param/param_get
ROS-Service Type: core_api/ParamGet, below is its description
#Request : Param id to get
string param_id
#Response: Param info of requested param
core_api/ParamInfo param_info
#Response : success=true if command is successful.
bool success
#Response : error message, if any
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: bool Param::param_get(std::string param_id, std::string ¶m_value)
Arguments:
param_id: ID of param to be created
param_value: Variable to store parameter value
Returns:
returns parameter value in param_value
returns 0 if the command is successful
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: param_get(param_id)
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_get
call srv:
:string param_id
response srv:
:core_api/ParamInfo param_info
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_get
call srv:
:string param_id
response srv:
:core_api/ParamInfo param_info
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/param/param_get'
JSON Request:
{ param_id: String }
JSON Response:
{ success: Boolean,
message: String,
param_info:{ param_value: String } }
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/param/param_get',
serviceType: 'core_api/ParamGet'
Request:
{ param_id: String }
Response:
{ success: Boolean,
message: String,
param_info:{ param_value: String } }
Example
rosservice call /flytos/param/param_get "param_id: ''"
#include <cpp_api/param_bridge.h>
Param param;
std::string param_id = "RTL_ALT";
std::string param_value;
param.param_get(param_id, param_value);
std::cout << "Parameter value: " << param_value << std::endl;
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#Get value of a specific parameter
drone.param_get('walk')
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
var msgdata={};
msgdata["param_id"]="RTL_ALT";
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/param/param_get",
success: function(data){
console.log(data.param_info.param_value);
}
});
var paramGet = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/param/param_get',
serviceType : 'core_api/ParamGet'
});
var request = new ROSLIB.ServiceRequest({
param_id: 'RTL_ALT'
});
paramGet.callService(request, function(result) {
console.log('Result for service call on '
+ paramGet.name
+ ': '
+ result.param_info.param_value);
});
Example response
success:True,
param_info:{ param_value: '6.00'}
param_value = 6
0
String - the value of the param
{
success:True,
param_info:{ param_value: '6.00'}
}
{
success:True,
param_info:{ param_value: '6.00'}
}
Description:
This API gets the value of a particular parameter specified.
Parameters:
Following parameters are applicable in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
param_id | string | Name of the parameter |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
param_value | string | value of the parameter |
ROS endpoint:
APIs in FlytOS are derived from/wrapped around the core services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/param/param_get
- Service Type:
ParamGet
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port **80*8. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/param/param_get
- JSON Request:
{ param_id: String }
- JSON Response:
{ success: Boolean message: String param_info:{param_value: String} }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/param/param_get
- serviceType:
core_api/paramGet
Parameter Save
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/param/param_save
ROS-Service Type: core_api/ParamSave, below is its description
#Request : Null
#Response : success=true if command is successful.
bool success
#Response : error message, if any
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: bool Param::param_save(void)
Arguments: Null
Returns: returns 0 if the command is successful
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: param_save()
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_save
call srv: Null
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_save
call srv: Null
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/param/param_save'
JSON Response:
{ success: Boolean,
message: String, }
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/param/param_save',
serviceType: 'core_api/ParamSave'
Response:
{ success: Boolean,
message: String
}
Example
rosservice call /flytos/param/param_save "{}"
#include <cpp_api/param_bridge.h>
Param param;
param.param_save()
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#Get value of a specific parameter
drone.param_save()
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/param/param_save",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var paramSave = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/param/param_save',
serviceType : 'core_api/ParamSave'
});
var request = new ROSLIB.ServiceRequest({});
paramSave.callService(request, function(result) {
console.log('Result for service call on '
+ paramSave.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
Bool - True, if action successful
{
success:True
}
{
success:True
}
Description:
This API saves the parameters to a file which allows data retention on reboot of FlytOS running systems.
Parameters:
Following parameters are applicable in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
ROS endpoint:
APIs in FlytOS are derived from / wrapped around the core services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/param/param_save
- Service Type:
ParamSave
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
GET http://<ip>/ros/<namespace>/param/param_save
- JSON Response:
{ success: Boolean message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace
>/param/param_save` - serviceType:
core_api/ParamSave
Parameter Load
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/param/param_load
ROS-Service Type: core_api/ParamLoad, below is its description
#Request : Null
#Response : success=true if command is successful.
bool success
#Response : error message, if any
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: bool Param::param_load(void)
Arguments: Null
Returns: returns 0 if the command is successful
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: param_load()
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_load
call srv: Null
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_load
call srv: Null
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/param/param_load'
JSON Response:
{ success: Boolean,
message: String, }
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/param/param_load',
serviceType: 'core_api/ParamLoad'
Response:
{ success: Boolean,
message: String
}
Example
rosservice call /flytos/param/param_load "{}"
#include <cpp_api/param_bridge.h>
Param param;
param.param_load()
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#Get value of a specific parameter
drone.param_load()
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/param/param_load",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var paramLoad = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/param/param_load',
serviceType : 'core_api/ParamLoad'
});
var request = new ROSLIB.ServiceRequest({});
paramLoad.callService(request, function(result) {
console.log('Result for service call on '
+ paramLoad.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
Bool - True, if action successful
{
success:True
}
{
success:True
}
Description:
This API loads parameters from a file where parameters were saved before or a newly uploaded param file.
Parameters:
Following parameters are applicable in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
ROS endpoint:
APIs in FlytOS are derived from/wrapped around the core services in ROS. Onboard service clients in rospy/roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type: `Ros Service
- Name:
/<namespace>/param/param_load
- Service Type:
ParamLoad
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
GET http://<ip>/ros/<namespace>/param/param_load
- JSON Response:
{ success: Boolean, message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/param/param_load
- serviceType:
core_api/ParamLoad
Parameter Create
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/param/param_create
ROS-Service Type: core_api/ParamCreate, below is its description
#Request : Info of parameter to be created
core_api/ParamInfo param_info
#Response : success=true if command is successful.
bool success
#Response : error message, if any
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: bool Param::param_create(std::string param_id, std::string param_value)
Arguments:
param_id: ID of param to be created
param_value: Value of param to be created
Returns: returns 0 if the command is successful
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: param_create(param_id, param_value)
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_create
call srv:
:core_api/ParamInfo param_info
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_create
call srv:
:core_api/ParamInfo param_info
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/param/param_create'
JSON Request:
{ param_info:{
param_id: String,
param_value: String
} }
JSON Response:
{ success: Boolean,
message: String, }
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/param/param_create',
serviceType: 'core_api/ParamCreate'
Request:
{ param_info:{
param_id: String,
param_value: String
} }
Response:
{ success: Boolean,
message: String
}
Example
rosservice call /flytos/param/param_create "param_info:
param_id: ''
param_value: ''"
#include <cpp_api/param_bridge.h>
Param param;
std::string param_id = "RTL_ALT";
std::string param_value = "5";
param.param_create(param_id, param_value);
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#Get value of a specific parameter
drone.param_create('walk', 'off')
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
var msgdata={};
msgdata["param_info"]={};
msgdata.param_info["param_id"]="RTL_ALT";
masdata.param_info["param_value"]='5.0;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/param/param_create",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var paramCreate = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/param/param_create',
serviceType : 'core_api/ParamCreate'
});
var request = new ROSLIB.ServiceRequest({
param_info:{
param_id: String,
param_value: String
}
});
paramCreate.callService(request, function(result) {
console.log('Result for service call on '
+ paramCreate.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
Bool - True, if action successful
{
success:True
}
{
success:True
}
Description:
This API creates a new parameter.
Parameters:
Following parameters are applicable in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
param_id | string | Name of the parameter |
param_value | string | Value for the parameter |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
ROS endpoint:
APIs in FlytOS are derived from/wrapped around the core services in ROS. Onboard service clients in rospy/roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/param/param_create
- Service Type:
ParamCreate
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/param/param_create
- JSON Request:
{ param_info:{ param_id: String, param_value: String } }
- JSON Response:
{ success: Boolean, message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/param/param_create
- serviceType:
core_api/ParamCreate
Parameter Delete
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/param/param_delete
ROS-Service Type: core_api/ParamDelete, below is its description
#Request : Info of parameter to be deleted
string param_id
#Response : success=true if command is successful.
bool success
#Response : error message, if any
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: bool Param::param_delete(std::string param_id)
Arguments:
param_id: ID of param to be deleted
Returns: returns 0 if the command is successful
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: param_delete()
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_delete
call srv:
:string param_id
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_delete
call srv:
:string param_id
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/param/param_delete'
JSON Request:
{ param_id: String }
JSON Response:
{ success: Boolean,
message: String, }
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/param/param_delete',
serviceType: 'core_api/ParamDelete'
Request:
{ param_id: String }
Response:
{ success: Boolean,
message: String, }
Example
rosservice call /flytos/param/param_delete "param_id: ''"
#include <cpp_api/param_bridge.h>
Param param;
std::string param_id = "RTL_ALT";
param.param_delete(param_id);
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#Get value of a specific parameter
drone.param_delete()
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
var msgdata={};
msgdata["param_id"]='RTL_ALT;
$.ajax({
type: "POST",
dataType: "json",
data: JSON.stringify(msgdata),
url: "http://<ip>/ros/<namespace>/param/param_delete",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var paramDelete = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/param/param_delete',
serviceType : 'core_api/ParamDelete'
});
var request = new ROSLIB.ServiceRequest({
param_id: String
});
paramDelete.callService(request, function(result) {
console.log('Result for service call on '
+ paramDelete.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
Bool - True, if action successful
{
success:True
}
{
success:True
}
Description:
This API deletes a parameter from FlytOS.
Parameters:
Following parameters are applicable in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
param_id | string | Name of the paramter to be deleted |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
ROS endpoint:
APIs in FlytOS are derived from / wrapped around the core services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/param/param_delete
- Service Type:
ParamDelete
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/ros/<namespace>/param/param_delete
- JSON Request:
{ param_id: String }
- JSON Response:
{ success: Boolean, message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/param/param_delete
- serviceType:
core_api/ParamDelete
Parameter Reset
Definition
# API call described below requires shell access, either login to the device by connecting a monitor or use ssh for remote login.
ROS-Service Name: /<namespace>/param/param_reset
ROS-Service Type: core_api/ParamReset, below is its description
#Request : Null
#Response : success=true if command is successful.
bool success
#Response : error message, if any
string message
// C++ API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from C++.
Function Definition: bool Param::param_reset(void)
Arguments: Null
Returns: returns 0 if the command is successful
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Class: flyt_python.API.navigation
Function: param_reset()
// ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_reset
call srv: Null
response srv:
:bool success
:string message
# ROS services and topics are accessible from onboard scripts only.
Type: Ros Service
Name: /<namespace>/param/param_reset
call srv: Null
response srv:
:bool success
:string message
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/ros/<namespace>/param/param_reset'
JSON Response:
{ success: Boolean,
message: String, }
This is a Websocket call for the API. Make sure you
initialise the websocket using websocket initialising
API and replace namespace with the namespace of
the FlytOS running device before calling the API
with websocket.
name: '/<namespace>/param/param_reset',
serviceType: 'core_api/ParamReset'
Response:
{ success: Boolean,
message: String, }
Example
rosservice call /flytos/param/param_reset "{}"
#include <cpp_api/param_bridge.h>
Param param;
param.param_reset()
# create flyt_python navigation class instance
from flyt_python import API
drone = API.navigation()
# wait for interface to initialize
time.sleep(3.0)
#Get value of a specific parameter
drone.param_reset()
// Please refer to Roscpp documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(c%2B%2B)
# Please refer to Rospy documentation for sample service clients. http://wiki.ros.org/ROS/Tutorials/WritingServiceClient(python)
$.ajax({
type: "GET",
dataType: "json",
url: "http://<ip>/ros/<namespace>/param/param_reset",
success: function(data){
console.log(data.success);
console.log(data.message);
}
});
var paramReset = new ROSLIB.Service({
ros : ros,
name : '/<namespace>/param/param_reset',
serviceType : 'core_api/ParamReset'
});
var request = new ROSLIB.ServiceRequest({});
paramReset.callService(request, function(result) {
console.log('Result for service call on '
+ paramReset.name
+ ': '
+ result.success
+': '
+ result.message);
});
Example response
success: true
0
Bool - True, if action successful
{
success:True
}
{
success:True
}
Description:
This API resets all the parameter value to the last save parameter state.
Parameters:
Following parameters are applicable for onboard C++ and Python scripts. Scroll down for their counterparts in RESTful, Websocket, ROS. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
x, y, z | float | Position Setpoint in NED-Frame (in body-frame if body_frame=true) |
yaw | float | Yaw Setpoint in radians |
yaw_valid | bool | Must be set to true, if yaw |
tolerance | float | Acceptance radius in meters, default value=1.0m |
relative | bool | If true, position setpoints relative to current position is sent |
async | bool | If true, asynchronous mode is set |
body_frame | bool | If true, position setpoints are relative with respect to body frame |
Output:
Parameter | Type | Description |
---|---|---|
success | bool | true if action successful |
message | string | debug message |
API usage information:
ROS endpoint:
APIs in FlytOS are derived from / wrapped around the core services in ROS. Onboard service clients in rospy / roscpp can call these APIs. Take a look at roscpp and rospy API definition for message structure.
- Type:
Ros Service
- Name:
/<namespace>/param/param_reset
- Service Type:
ParamReset
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
GET http://<ip>/ros/<namespace>/param/param_reset
- JSON Response:
{ success: Boolean, message: String }
Websocket endpoint:
Websocket APIs can be called from javascript using roslibjs library.
Java websocket clients are supported using rosjava.
- name:
/<namespace>/param/param_reset
- serviceType:
core_api/ParamReset
Video Streaming API
Definition
# Python API described below can be used in onboard scripts only. For remote scripts you can use http client libraries to call FlytOS REST endpoints from Python.
Not Implemented
This is a REST call for the API. Make sure to replace
ip: ip of the FlytOS running device
namespace: namespace used by the FlytOS device.
URL: 'http://<ip>/list_streams'
JSON Request:
{ namespace: String}
JSON Response:
{ stream1: String,
stream2: String,.... }
NA
Example
Not Implemented
Not Implemented
Not Implemented
Not Implemented
Not Implemented
var msgdata=[];
msgdata['namespace']='flytpod';
// Use getnamespace API to know the namespace
$.ajax({
type: "POST",
dataType: "json",
url: "http://<ip>/list_streams",
success: function(data){
console.log(data['stream1']+" "+data['stream2']);
}
});
NA
Example response
Not Implemented
Not Implemented
Not Implemented
Not Implemented
Not Implemented
{
stream1: <link to stream1>,
stream2: <link to stream2>,
stream3: <link to stream3>,
stream4: <link to stream4>,
stream5: <link to stream5>,
.
.
.
}
NA
Description:
This API allows to get the list of video streams avalibale and view the live stream.
API usage information:
To view the video of a particular stream from the list of streams you need to create an img tag add the link to its source.
<img src='http://<ip>/stream?topic=<link to stream1>'>
Tip: You can add the following parameters as query string to the link for lighter or better resolution video quality. width, height, quality, rate:1/2/3
1. 1 will send out every frame,
2. 2 will send out every second frame,
3. 3 every third and so on…
Tip: To stop the video stream you need to delete the img tag completely.
Tip: To take a snapshot of the stream replace the word stream with snapshot in the link.
<img src='http://<ip>/snapshot?topic=<link to stream1>'>
Parameters:
Following parameters are applicable in RESTful, Websocket. However the description of these parameters applies to all platforms.
Arguments:
Argument | Type | Description |
---|---|---|
namespace | string | namespace used in FlytOS |
Output:
Parameter | Type | Description |
---|---|---|
stream1 | string | link of the video stream1 |
stream2 | string | link of the video stream2 |
stream3 | string | link of the video stream3 |
. . .
RESTful endpoint:
FlytOS hosts a RESTful server which listens on port 80. RESTful APIs can be called from remote platform of your choice.
- URL:
POST http://<ip>/list_streams
JSON Request:
{ namespace: <namespace of FlytOS> }
JSON Response:
{ stream1: <link to stream1>, stream2: <link to stream2>, stream3: <link to stream3>, stream4: <link to stream4>, stream5: <link to stream5>, . . . }