Merge pull request #1878 from anton-matosov/ServoGimbal

Servo gimbal
This commit is contained in:
Lorenz Meier 2015-03-07 09:44:47 +01:00
commit 9495ec4f5a
10 changed files with 708 additions and 6 deletions

View File

@ -38,10 +38,18 @@
"build_systems":
[
{
"name": "PX4",
"name": "PX4: make all",
"working_dir": "${project_path}",
"file_regex": "^(..[^:]*):([0-9]+):?([0-9]+)?:? (.*)$",
"cmd": ["make"]
"cmd": ["make -j8"],
"shell": true
},
{
"name": "PX4: make and upload",
"working_dir": "${project_path}",
"file_regex": "^(..[^:]*):([0-9]+):?([0-9]+)?:? (.*)$",
"cmd": ["make upload px4fmu-v2_default -j8"],
"shell": true
}
]
}

View File

@ -29,3 +29,10 @@ set MIXER sk450_deadcat
set PWM_OUT 1234
set PWM_MIN 1050
set PWM_AUX_OUT 1234
# set PWM_AUX_MIN 900
# set PWM_AUX_MAX 2100
set PWM_AUX_RATE 100
gimbal start

View File

@ -11,7 +11,7 @@ then
# Load main mixer
#
if [ $MIXER_AUX == none -a $USE_IO == yes ]
if [ $MIXER_AUX == none -a $USE_IO == yes ]
then
set MIXER_AUX $MIXER.aux
fi
@ -103,6 +103,7 @@ then
#
set MIXER_AUX_FILE none
set OUTPUT_AUX_DEV /dev/pwm_output1
if [ -f $SDCARD_MIXERS_PATH/$MIXER_AUX.mix ]
then
@ -119,10 +120,43 @@ then
then
if fmu mode_pwm
then
mixer load /dev/pwm_output1 $MIXER_AUX_FILE
mixer load $OUTPUT_AUX_DEV $MIXER_AUX_FILE
else
tone_alarm $TUNE_ERR
fi
if [ $PWM_AUX_OUT != none ]
then
#
# Set PWM_AUX output frequency
#
if [ $PWM_AUX_RATE != none ]
then
pwm rate -c $PWM_AUX_OUT -r $PWM_AUX_RATE -d $OUTPUT_AUX_DEV
fi
#
# Set disarmed, min and max PWM_AUX values
#
if [ $PWM_AUX_DISARMED != none ]
then
pwm disarmed -c $PWM_AUX_OUT -p $PWM_AUX_DISARMED -d $OUTPUT_AUX_DEV
fi
if [ $PWM_AUX_MIN != none ]
then
pwm min -c $PWM_AUX_OUT -p $PWM_AUX_MIN -d $OUTPUT_AUX_DEV
fi
if [ $PWM_AUX_MAX != none ]
then
pwm max -c $PWM_AUX_OUT -p $PWM_AUX_MAX -d $OUTPUT_AUX_DEV
fi
fi
if [ $FAILSAFE_AUX != none ]
then
pwm failsafe -d $OUTPUT_AUX_DEV $FAILSAFE
fi
fi
fi
unset OUTPUT_DEV

View File

@ -109,6 +109,11 @@ then
set PWM_DISARMED none
set PWM_MIN none
set PWM_MAX none
set PWM_AUX_OUT none
set PWM_AUX_RATE none
set PWM_AUX_DISARMED none
set PWM_AUX_MIN none
set PWM_AUX_MAX none
set MK_MODE none
set FMU_MODE pwm
set MAVLINK_F default

View File

@ -0,0 +1,38 @@
Gimbal / payload mixer for PX4FMU
===========================
Configuration with 2 gimbals:
- 2 axes inline GoPro gimbal (pitch, roll)
- 2 axes FPV gimbal (pitch, yaw), physically attached GoPro gimbal's roll stabilization
-----------------------------------------------------
# gimbal roll
M: 1
O: 10000 10000 0 -10000 10000
S: 2 0 -11500 -10000 900 -10000 10000
# gimbal pitch
M: 1
O: 10000 10000 0 -10000 10000
S: 2 1 12000 12000 2000 -10000 10000
# FPV gimbal yaw (not implemented, yet)
M: 1
O: 10000 10000 0 -10000 10000
S: 2 2 10000 10000 0 -10000 10000
# FPV gimbal pitch
M: 1
O: 10000 10000 0 -10000 10000
S: 2 1 -12000 -12000 -3000 -10000 10000
# reserved, not used
M: 1
O: 10000 10000 0 -10000 10000
S: 2 4 10000 10000 0 -10000 10000
# parachute
M: 1
O: 10000 10000 0 -10000 10000
S: 2 7 10000 10000 0 -10000 10000

View File

@ -1,4 +1,4 @@
Multirotor mixer for PX4FMU
Multirotor mixer for PX4IO
===========================
This file defines a single mixer for a quadrotor in SK450 DeadCat configuration. All controls are mixed 100%.

View File

@ -44,6 +44,7 @@ MODULES += modules/sensors
MODULES += drivers/mkblctrl
MODULES += drivers/px4flow
MODULES += drivers/oreoled
MODULES += drivers/gimbal
#
# System commands

View File

@ -0,0 +1,541 @@
/****************************************************************************
*
* Copyright (c) 2014, 2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file gimbal.cpp
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Anton Matosov <anton.matosov@gmail.com>
*
* Driver to control a gimbal - relies on input via telemetry or RC
* and output via the standardized control group #2 and a mixer.
*/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdlib.h>
#include <stdbool.h>
#include <semaphore.h>
#include <string.h>
#include <fcntl.h>
#include <poll.h>
#include <errno.h>
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <termios.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_range_finder.h>
#include <drivers/device/device.h>
#include <drivers/device/ringbuffer.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/vehicle_attitude.h>
#include <board_config.h>
#include <mathlib/math/test/test.hpp>
#include <mathlib/math/Quaternion.hpp>
/* Configuration Constants */
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
# undef ERROR
#endif
static const int ERROR = -1;
#ifndef CONFIG_SCHED_WORKQUEUE
# error This requires CONFIG_SCHED_WORKQUEUE.
#endif
#define GIMBAL_DEVICE_PATH "/dev/gimbal"
#define GIMBAL_UPDATE_INTERVAL (5 * 1000)
#define GIMBALIOCATTCOMPENSATE 1
class Gimbal : public device::CDev
{
public:
Gimbal();
virtual ~Gimbal();
virtual int init();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
/**
* Diagnostics - print some basic information about the driver.
*/
void print_info();
protected:
virtual int probe();
private:
float _min_distance;
float _max_distance;
work_s _work;
int _vehicle_command_sub;
int _att_sub;
bool _attitude_compensation;
bool _initialized;
orb_advert_t _actuator_controls_2_topic;
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
perf_counter_t _buffer_overflows;
/**
* Initialise the automatic measurement state machine and start it.
*
* @note This function is called at open and error time. It might make sense
* to make it more aggressive about resetting the bus in case of errors.
*/
void start();
/**
* Stop the automatic measurement state machine.
*/
void stop();
/**
* Perform a poll cycle; collect from the previous measurement
* and start a new one.
*/
void cycle();
/**
* Static trampoline from the workq context; because we don't have a
* generic workq wrapper yet.
*
* @param arg Instance pointer for the driver that is polling.
*/
static void cycle_trampoline(void *arg);
};
/*
* Driver 'main' command.
*/
extern "C" __EXPORT int gimbal_main(int argc, char *argv[]);
Gimbal::Gimbal() :
CDev("Gimbal", GIMBAL_DEVICE_PATH),
_vehicle_command_sub(-1),
_att_sub(-1),
_attitude_compensation(true),
_initialized(false),
_actuator_controls_2_topic(-1),
_sample_perf(perf_alloc(PC_ELAPSED, "gimbal_read")),
_comms_errors(perf_alloc(PC_COUNT, "gimbal_comms_errors")),
_buffer_overflows(perf_alloc(PC_COUNT, "gimbal_buffer_overflows"))
{
// disable debug() calls
_debug_enabled = false;
// work_cancel in the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work));
}
Gimbal::~Gimbal()
{
/* make sure we are truly inactive */
stop();
::close(_actuator_controls_2_topic);
::close(_vehicle_command_sub);
}
int
Gimbal::init()
{
int ret = ERROR;
/* do regular cdev init */
if (CDev::init() != OK) {
goto out;
}
start();
ret = OK;
out:
return ret;
}
int
Gimbal::probe()
{
return OK;
}
int
Gimbal::ioctl(struct file *filp, int cmd, unsigned long arg)
{
switch (cmd) {
case GIMBALIOCATTCOMPENSATE:
_attitude_compensation = (arg != 0);
return OK;
default:
/* give it to the superclass */
return CDev::ioctl(filp, cmd, arg);
}
}
ssize_t
Gimbal::read(struct file *filp, char *buffer, size_t buflen)
{
return 0;
}
void
Gimbal::start()
{
/* schedule a cycle to start things */
work_queue(LPWORK, &_work, (worker_t)&Gimbal::cycle_trampoline, this, 1);
}
void
Gimbal::stop()
{
work_cancel(LPWORK, &_work);
}
void
Gimbal::cycle_trampoline(void *arg)
{
Gimbal *dev = static_cast<Gimbal *>(arg);
dev->cycle();
}
void
Gimbal::cycle()
{
if (!_initialized) {
/* get a subscription handle on the vehicle command topic */
_vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command));
/* get a publication handle on actuator output topic */
struct actuator_controls_s zero_report;
memset(&zero_report, 0, sizeof(zero_report));
zero_report.timestamp = hrt_absolute_time();
_actuator_controls_2_topic = orb_advertise(ORB_ID(actuator_controls_2), &zero_report);
if (_actuator_controls_2_topic < 0) {
warnx("advert err");
}
_initialized = true;
}
bool updated = false;
perf_begin(_sample_perf);
float roll = 0.0f;
float pitch = 0.0f;
float yaw = 0.0f;
if (_attitude_compensation) {
if (_att_sub < 0) {
_att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
}
vehicle_attitude_s att;
orb_copy(ORB_ID(vehicle_attitude), _att_sub, &att);
roll = -att.roll;
pitch = -att.pitch;
yaw = att.yaw;
updated = true;
}
struct vehicle_command_s cmd;
bool cmd_updated;
orb_check(_vehicle_command_sub, &cmd_updated);
if (cmd_updated) {
orb_copy(ORB_ID(vehicle_command), _vehicle_command_sub, &cmd);
VEHICLE_MOUNT_MODE mountMode = (VEHICLE_MOUNT_MODE)cmd.param7;
debug("cmd: %d, mountMode %d | param1: %8.4f param2: %8.4f", cmd.command, mountMode, (double)cmd.param1, (double)cmd.param2);
if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL && mountMode == VEHICLE_MOUNT_MODE_MAVLINK_TARGETING) {
/* Convert to range -1 ... 1, which corresponds to -180deg ... 180deg */
roll += 1.0f / M_PI_F * M_DEG_TO_RAD_F * cmd.param1;
pitch += 1.0f / M_PI_F * M_DEG_TO_RAD_F * cmd.param2;
yaw += 1.0f / M_PI_F * M_DEG_TO_RAD_F * cmd.param3;
updated = true;
}
if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT && mountMode == VEHICLE_MOUNT_MODE_MAVLINK_TARGETING) {
float gimbalDirectionQuat[] = {cmd.param1, cmd.param2, cmd.param3, cmd.param4};
math::Vector<3> gimablDirectionEuler = math::Quaternion(gimbalDirectionQuat).to_dcm().to_euler();
roll += gimablDirectionEuler(0);
pitch += gimablDirectionEuler(1);
yaw += gimablDirectionEuler(2);
updated = true;
}
}
if (updated) {
struct actuator_controls_s controls;
// debug("publishing | roll: %8.4f pitch: %8.4f yaw: %8.4f", (double)roll, (double)pitch, (double)yaw);
/* fill in the final control values */
controls.timestamp = hrt_absolute_time();
controls.control[0] = roll;
controls.control[1] = pitch;
controls.control[2] = yaw;
/* publish it */
orb_publish(ORB_ID(actuator_controls_2), _actuator_controls_2_topic, &controls);
}
/* notify anyone waiting for data */
poll_notify(POLLIN);
perf_end(_sample_perf);
/* schedule a fresh cycle call when the measurement is done */
work_queue(LPWORK,
&_work,
(worker_t)&Gimbal::cycle_trampoline,
this,
USEC2TICK(GIMBAL_UPDATE_INTERVAL));
}
void
Gimbal::print_info()
{
perf_print_counter(_sample_perf);
perf_print_counter(_comms_errors);
perf_print_counter(_buffer_overflows);
}
/**
* Local functions in support of the shell command.
*/
namespace gimbal
{
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
# undef ERROR
#endif
const int ERROR = -1;
Gimbal *g_dev;
void start();
void stop();
void test();
void reset();
void info();
/**
* Start the driver.
*/
void
start()
{
if (g_dev != nullptr) {
errx(1, "already started");
}
/* create the driver */
g_dev = new Gimbal();
if (g_dev == nullptr) {
goto fail;
}
if (OK != g_dev->init()) {
goto fail;
}
exit(0);
fail:
if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
}
errx(1, "driver start failed");
}
/**
* Stop the driver
*/
void stop()
{
if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
} else {
errx(1, "driver not running");
}
exit(0);
}
/**
* Perform some basic functional tests on the driver;
* make sure we can collect data from the sensor in polled
* and automatic modes.
*/
void
test()
{
int fd = open(GIMBAL_DEVICE_PATH, O_RDONLY);
if (ioctl(fd, GIMBALIOCATTCOMPENSATE, 1) < 0) {
err(1, "failed enabling compensation");
}
errx(0, "PASS");
}
/**
* Reset the driver.
*/
void
reset()
{
int fd = open(GIMBAL_DEVICE_PATH, O_RDONLY);
if (fd < 0) {
err(1, "failed ");
}
// if (ioctl(fd, GIMBALIOCATTCOMPENSATE, 1) < 0) {
// err(1, "failed enabling compensation");
// }
exit(0);
}
/**
* Print a little info about the driver.
*/
void
info()
{
if (g_dev == nullptr) {
errx(1, "driver not running");
}
printf("state @ %p\n", g_dev);
g_dev->print_info();
exit(0);
}
} // namespace
int
gimbal_main(int argc, char *argv[])
{
/*
* Start/load the driver.
*/
if (!strcmp(argv[1], "start")) {
gimbal::start();
}
/*
* Stop the driver
*/
if (!strcmp(argv[1], "stop")) {
gimbal::stop();
}
/*
* Test the driver/device.
*/
if (!strcmp(argv[1], "test")) {
gimbal::test();
}
/*
* Reset the driver.
*/
if (!strcmp(argv[1], "reset")) {
gimbal::reset();
}
/*
* Print driver information.
*/
if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) {
gimbal::info();
}
errx(1, "unrecognized command, try 'start', 'stop', 'reset', 'test' or 'info'");
}

View File

@ -0,0 +1,42 @@
############################################################################
#
# Copyright (c) 2014, 2015 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# Makefile to build the gimbal high-level controller
#
MODULE_COMMAND = gimbal
SRCS = gimbal.cpp
MAXOPTIMIZATION = -Os

View File

@ -38,6 +38,7 @@
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Anton Matosov <anton.matosov@gmail.com>
*/
#ifndef TOPIC_VEHICLE_COMMAND_H_
@ -85,6 +86,15 @@ enum VEHICLE_CMD {
VEHICLE_CMD_DO_REPEAT_SERVO = 184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
VEHICLE_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_CONTROL_VIDEO = 200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
VEHICLE_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */
VEHICLE_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */
VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */
VEHICLE_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */
VEHICLE_CMD_DO_LAST = 240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
@ -101,7 +111,7 @@ enum VEHICLE_CMD {
/**
* Commands for commander app.
*
* Should contain all of MAVLink's VEHICLE_CMD_RESULT values
* Should contain all of MAVLink's MAV_CMD_RESULT values
* but can contain additional ones.
*/
enum VEHICLE_CMD_RESULT {
@ -113,6 +123,22 @@ enum VEHICLE_CMD_RESULT {
VEHICLE_CMD_RESULT_ENUM_END = 5, /* | */
};
/**
* Commands for gimbal app.
*
* Should contain all of MAVLink's MAV_MOUNT_MODE values
* but can contain additional ones.
*/
typedef enum VEHICLE_MOUNT_MODE
{
VEHICLE_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | */
VEHICLE_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | */
VEHICLE_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */
VEHICLE_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */
VEHICLE_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */
VEHICLE_MOUNT_MODE_ENUM_END=5, /* | */
} VEHICLE_MOUNT_MODE;
/**
* @addtogroup topics
* @{