forked from Archive/PX4-Autopilot
Rename vmount to gimbal
This commit is contained in:
parent
853047c643
commit
490a0c473b
|
@ -234,7 +234,7 @@ fi
|
|||
|
||||
if param greater -s MNT_MODE_IN -1
|
||||
then
|
||||
vmount start
|
||||
gimbal start
|
||||
fi
|
||||
|
||||
if param greater -s TRIG_MODE 0
|
||||
|
|
|
@ -486,11 +486,11 @@ else
|
|||
. ${R}etc/init.d/rc.thermal_cal
|
||||
|
||||
#
|
||||
# Start vmount to control mounts such as gimbals, disabled by default.
|
||||
# Start gimbal to control mounts such as gimbals, disabled by default.
|
||||
#
|
||||
if param greater -s MNT_MODE_IN -1
|
||||
then
|
||||
vmount start
|
||||
gimbal start
|
||||
fi
|
||||
|
||||
# Check for flow sensor
|
||||
|
|
|
@ -150,7 +150,7 @@ simulator,CONFIG_MODULES_SIMULATOR=y
|
|||
temperature_compensation,CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
uuv_att_control,CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
uuv_pos_control,CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
vmount,CONFIG_MODULES_VMOUNT=y
|
||||
gimbal,CONFIG_MODULES_GIMBAL=y
|
||||
vtol_att_control,CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
bl_update,CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
dmesg,CONFIG_SYSTEMCMDS_DMESG=y
|
||||
|
|
|
@ -74,7 +74,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -31,7 +31,7 @@ CONFIG_MODULES_NAVIGATOR=y
|
|||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
|
|
|
@ -71,7 +71,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -56,7 +56,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_DYN=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
|
|
|
@ -76,7 +76,7 @@ CONFIG_MODULES_ROVER_POS_CONTROL=y
|
|||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -77,7 +77,7 @@ CONFIG_MODULES_ROVER_POS_CONTROL=y
|
|||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -72,7 +72,7 @@ CONFIG_MODULES_ROVER_POS_CONTROL=y
|
|||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -74,7 +74,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -58,7 +58,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_DYN=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
|
|
|
@ -69,7 +69,7 @@ CONFIG_MODULES_ROVER_POS_CONTROL=y
|
|||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -62,7 +62,7 @@ CONFIG_MODULES_ROVER_POS_CONTROL=y
|
|||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -79,7 +79,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -52,7 +52,7 @@ CONFIG_MODULES_NAVIGATOR=y
|
|||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
|
|
|
@ -74,7 +74,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -70,7 +70,7 @@ CONFIG_MODULES_ROVER_POS_CONTROL=y
|
|||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -72,7 +72,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -72,7 +72,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -71,7 +71,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
|
|
|
@ -72,7 +72,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
|
|
|
@ -70,7 +70,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -73,7 +73,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -74,7 +74,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -72,7 +72,7 @@ CONFIG_MODULES_ROVER_POS_CONTROL=y
|
|||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
|
|
|
@ -76,7 +76,7 @@ CONFIG_MODULES_ROVER_POS_CONTROL=y
|
|||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
|
|
|
@ -48,7 +48,7 @@ CONFIG_MODULES_MC_RATE_CONTROL=y
|
|||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
|
|
|
@ -77,7 +77,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -78,7 +78,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -75,7 +75,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -32,7 +32,7 @@ CONFIG_MODULES_SIH=n
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=n
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=n
|
||||
CONFIG_MODULES_VMOUNT=n
|
||||
CONFIG_MODULES_GIMBAL=n
|
||||
CONFIG_SYSTEMCMDS_SERIAL_TEST=n
|
||||
CONFIG_BOARD_CONSTRAINED_FLASH=y
|
||||
CONFIG_BOARD_TESTING=y
|
||||
|
|
|
@ -80,7 +80,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
|
|
|
@ -28,6 +28,6 @@ CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
|
|||
CONFIG_MODULES_ROVER_POS_CONTROL=n
|
||||
CONFIG_MODULES_SIH=n
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
|
||||
CONFIG_MODULES_VMOUNT=n
|
||||
CONFIG_MODULES_GIMBAL=n
|
||||
CONFIG_BOARD_CONSTRAINED_FLASH=y
|
||||
CONFIG_BOARD_TESTING=y
|
||||
|
|
|
@ -80,7 +80,7 @@ CONFIG_MODULES_ROVER_POS_CONTROL=y
|
|||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
|
|
|
@ -72,7 +72,7 @@ CONFIG_MODULES_ROVER_POS_CONTROL=y
|
|||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -68,7 +68,7 @@ CONFIG_MODULES_ROVER_POS_CONTROL=y
|
|||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
|
|
|
@ -55,7 +55,7 @@ CONFIG_MODULES_SIH=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_DYN=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
|
|
|
@ -43,7 +43,7 @@ CONFIG_MODULES_SIMULATOR=y
|
|||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_DYN=y
|
||||
|
|
|
@ -53,7 +53,7 @@ CONFIG_MODULES_ROVER_POS_CONTROL=y
|
|||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_DYN=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
|
|
|
@ -39,7 +39,7 @@ CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
|||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
||||
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
|
||||
|
|
|
@ -59,7 +59,7 @@ CONFIG_MODULES_RC_UPDATE=y
|
|||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_VMOUNT=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
|
|
|
@ -31,8 +31,8 @@
|
|||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE drivers__vmount
|
||||
MAIN vmount
|
||||
MODULE drivers__gimbal
|
||||
MAIN gimbal
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
input.cpp
|
||||
|
@ -42,7 +42,7 @@ px4_add_module(
|
|||
output.cpp
|
||||
output_mavlink.cpp
|
||||
output_rc.cpp
|
||||
vmount.cpp
|
||||
gimbal.cpp
|
||||
DEPENDS
|
||||
geo
|
||||
)
|
|
@ -0,0 +1,5 @@
|
|||
menuconfig MODULES_GIMBAL
|
||||
bool "gimbal"
|
||||
default n
|
||||
---help---
|
||||
Enable support for GIMBAL
|
|
@ -36,12 +36,12 @@
|
|||
|
||||
#include <stdint.h>
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
/**
|
||||
* @struct ControlData
|
||||
* This defines the common API between an input and an output of the vmount driver.
|
||||
* This defines the common API between an input and an output of the gimbal driver.
|
||||
* Each output must support the (full) set of the commands, and an input can create all
|
||||
* or a subset of the types.
|
||||
*/
|
||||
|
@ -87,4 +87,4 @@ struct ControlData {
|
|||
};
|
||||
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -49,7 +49,7 @@
|
|||
#include <px4_platform_common/defines.h>
|
||||
#include <px4_platform_common/tasks.h>
|
||||
|
||||
#include "vmount_params.h"
|
||||
#include "gimbal_params.h"
|
||||
#include "input_mavlink.h"
|
||||
#include "input_rc.h"
|
||||
#include "input_test.h"
|
||||
|
@ -64,7 +64,7 @@
|
|||
#include <px4_platform_common/atomic.h>
|
||||
|
||||
using namespace time_literals;
|
||||
using namespace vmount;
|
||||
using namespace gimbal;
|
||||
|
||||
static px4::atomic<bool> thread_should_exit {false};
|
||||
static px4::atomic<bool> thread_running {false};
|
||||
|
@ -85,10 +85,10 @@ static void usage();
|
|||
static void update_params(ParameterHandles ¶m_handles, Parameters ¶ms);
|
||||
static bool initialize_params(ParameterHandles ¶m_handles, Parameters ¶ms);
|
||||
|
||||
static int vmount_thread_main(int argc, char *argv[]);
|
||||
extern "C" __EXPORT int vmount_main(int argc, char *argv[]);
|
||||
static int gimbal_thread_main(int argc, char *argv[]);
|
||||
extern "C" __EXPORT int gimbal_main(int argc, char *argv[]);
|
||||
|
||||
static int vmount_thread_main(int argc, char *argv[])
|
||||
static int gimbal_thread_main(int argc, char *argv[])
|
||||
{
|
||||
ParameterHandles param_handles;
|
||||
Parameters params {};
|
||||
|
@ -302,7 +302,7 @@ static int vmount_thread_main(int argc, char *argv[])
|
|||
return 0;
|
||||
}
|
||||
|
||||
int vmount_main(int argc, char *argv[])
|
||||
int gimbal_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 2) {
|
||||
PX4_ERR("missing command");
|
||||
|
@ -319,16 +319,16 @@ int vmount_main(int argc, char *argv[])
|
|||
|
||||
thread_should_exit.store(false);
|
||||
|
||||
int vmount_task = px4_task_spawn_cmd("vmount",
|
||||
int gimbal_task = px4_task_spawn_cmd("gimbal",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
2100,
|
||||
vmount_thread_main,
|
||||
gimbal_thread_main,
|
||||
nullptr);
|
||||
|
||||
int counter = 0;
|
||||
|
||||
while (!thread_running.load() && vmount_task >= 0) {
|
||||
while (!thread_running.load() && gimbal_task >= 0) {
|
||||
px4_usleep(5000);
|
||||
|
||||
if (++counter >= 100) {
|
||||
|
@ -336,7 +336,7 @@ int vmount_main(int argc, char *argv[])
|
|||
}
|
||||
}
|
||||
|
||||
if (vmount_task < 0) {
|
||||
if (gimbal_task < 0) {
|
||||
PX4_ERR("failed to start");
|
||||
return -1;
|
||||
}
|
||||
|
@ -529,12 +529,12 @@ Documentation how to use it is on the [gimbal_control](https://docs.px4.io/maste
|
|||
|
||||
### Examples
|
||||
Test the output by setting a angles (all omitted axes are set to 0):
|
||||
$ vmount test pitch -45 yaw 30
|
||||
$ gimbal test pitch -45 yaw 30
|
||||
)DESCR_STR");
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("vmount", "driver");
|
||||
PRINT_MODULE_USAGE_NAME("gimbal", "driver");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("test", "Test the output: set a fixed angle for one or multiple axes (vmount must be running)");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("test", "Test the output: set a fixed angle for one or multiple axes (gimbal must be running)");
|
||||
PRINT_MODULE_USAGE_ARG("roll|pitch|yaw <angle>", "Specify an axis and an angle in degrees", false);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
|
@ -37,7 +37,7 @@
|
|||
#include <stdint.h>
|
||||
#include <lib/parameters/param.h>
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
struct Parameters {
|
||||
|
@ -88,4 +88,4 @@ struct ParameterHandles {
|
|||
param_t mnt_rc_in_mode;
|
||||
};
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -34,7 +34,7 @@
|
|||
#include "input.h"
|
||||
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
InputBase::InputBase(Parameters ¶meters) :
|
||||
|
@ -56,4 +56,4 @@ void InputBase::control_data_set_lon_lat(ControlData &control_data, double lon,
|
|||
}
|
||||
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -35,9 +35,9 @@
|
|||
|
||||
#include "common.h"
|
||||
#include "math.h"
|
||||
#include "vmount_params.h"
|
||||
#include "gimbal_params.h"
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
struct Parameters;
|
||||
|
@ -67,4 +67,4 @@ protected:
|
|||
};
|
||||
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -43,7 +43,7 @@
|
|||
#include <math.h>
|
||||
#include <matrix/matrix/math.hpp>
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
InputMavlinkROI::InputMavlinkROI(Parameters ¶meters) :
|
||||
|
@ -273,9 +273,9 @@ InputMavlinkCmdMount::_process_command(ControlData &control_data, const vehicle_
|
|||
control_data.type_data.angle.frames[1] = ControlData::TypeData::TypeAngle::Frame::AngleAbsoluteFrame;
|
||||
control_data.type_data.angle.frames[2] = ControlData::TypeData::TypeAngle::Frame::AngleBodyFrame;
|
||||
|
||||
// vmount spec has roll on channel 0, MAVLink spec has pitch on channel 0
|
||||
// gimbal spec has roll on channel 0, MAVLink spec has pitch on channel 0
|
||||
const float roll = math::radians(vehicle_command.param2);
|
||||
// vmount spec has pitch on channel 1, MAVLink spec has roll on channel 1
|
||||
// gimbal spec has pitch on channel 1, MAVLink spec has roll on channel 1
|
||||
const float pitch = math::radians(vehicle_command.param1);
|
||||
// both specs have yaw on channel 2
|
||||
float yaw = math::radians(vehicle_command.param3);
|
||||
|
@ -694,9 +694,9 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_
|
|||
control_data.type_data.angle.frames[1] = ControlData::TypeData::TypeAngle::Frame::AngleAbsoluteFrame;
|
||||
control_data.type_data.angle.frames[2] = ControlData::TypeData::TypeAngle::Frame::AngleBodyFrame;
|
||||
|
||||
// vmount spec has roll on channel 0, MAVLink spec has pitch on channel 0
|
||||
// gimbal spec has roll on channel 0, MAVLink spec has pitch on channel 0
|
||||
const float roll = math::radians(vehicle_command.param2);
|
||||
// vmount spec has pitch on channel 1, MAVLink spec has roll on channel 1
|
||||
// gimbal spec has pitch on channel 1, MAVLink spec has roll on channel 1
|
||||
const float pitch = math::radians(vehicle_command.param1);
|
||||
// both specs have yaw on channel 2
|
||||
float yaw = math::radians(vehicle_command.param3);
|
||||
|
@ -970,4 +970,4 @@ void InputMavlinkGimbalV2::_read_control_data_from_position_setpoint_sub(Control
|
|||
control_data.type_data.lonlat.altitude = position_setpoint_triplet.current.alt;
|
||||
}
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -51,7 +51,7 @@
|
|||
#include <lib/geo/geo.h>
|
||||
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
class InputMavlinkROI : public InputBase
|
||||
|
@ -130,4 +130,4 @@ private:
|
|||
uint8_t _cur_roi_mode = vehicle_roi_s::ROI_NONE;
|
||||
};
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -42,7 +42,7 @@
|
|||
#include <px4_platform_common/defines.h>
|
||||
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
InputRC::InputRC(Parameters ¶meters) :
|
||||
|
@ -219,4 +219,4 @@ void InputRC::print_status() const
|
|||
_parameters.mnt_man_pitch, _parameters.mnt_man_yaw);
|
||||
}
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -35,10 +35,10 @@
|
|||
#pragma once
|
||||
|
||||
#include "input.h"
|
||||
#include "vmount_params.h"
|
||||
#include "gimbal_params.h"
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
class InputRC : public InputBase
|
||||
|
@ -64,4 +64,4 @@ private:
|
|||
float _last_set_aux_values[3] {};
|
||||
};
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -38,7 +38,7 @@
|
|||
#include <lib/mathlib/mathlib.h>
|
||||
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
InputTest::InputTest(Parameters ¶meters) :
|
||||
|
@ -101,4 +101,4 @@ void InputTest::set_test_input(int roll_deg, int pitch_deg, int yaw_deg)
|
|||
_has_been_set.store(true);
|
||||
}
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -36,7 +36,7 @@
|
|||
#include "input.h"
|
||||
#include <px4_platform_common/atomic.h>
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
class InputTest : public InputBase
|
||||
|
@ -61,4 +61,4 @@ private:
|
|||
};
|
||||
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -43,7 +43,7 @@
|
|||
#include <mathlib/mathlib.h>
|
||||
#include <matrix/math.hpp>
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
OutputBase::OutputBase(const Parameters ¶meters)
|
||||
|
@ -241,5 +241,5 @@ void OutputBase::set_stabilize(bool roll_stabilize, bool pitch_stabilize, bool y
|
|||
_stabilize[2] = yaw_stabilize;
|
||||
}
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
||||
|
|
@ -35,7 +35,7 @@
|
|||
#pragma once
|
||||
|
||||
#include "common.h"
|
||||
#include "vmount_params.h"
|
||||
#include "gimbal_params.h"
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <lib/geo/geo.h>
|
||||
#include <uORB/Publication.hpp>
|
||||
|
@ -44,7 +44,7 @@
|
|||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
class OutputBase
|
||||
|
@ -98,4 +98,4 @@ private:
|
|||
};
|
||||
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -39,7 +39,7 @@
|
|||
#include <px4_platform_common/defines.h>
|
||||
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
OutputMavlinkV1::OutputMavlinkV1(const Parameters ¶meters)
|
||||
|
@ -97,8 +97,8 @@ void OutputMavlinkV1::update(const ControlData &control_data, bool new_setpoints
|
|||
vehicle_command.timestamp = t;
|
||||
vehicle_command.command = vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONTROL;
|
||||
|
||||
// vmount spec has roll, pitch on channels 0, 1, respectively; MAVLink spec has roll, pitch on channels 1, 0, respectively
|
||||
// vmount uses radians, MAVLink uses degrees
|
||||
// gimbal spec has roll, pitch on channels 0, 1, respectively; MAVLink spec has roll, pitch on channels 1, 0, respectively
|
||||
// gimbal uses radians, MAVLink uses degrees
|
||||
vehicle_command.param1 = math::degrees(_angle_outputs[1] + math::radians(_parameters.mnt_off_pitch));
|
||||
vehicle_command.param2 = math::degrees(_angle_outputs[0] + math::radians(_parameters.mnt_off_roll));
|
||||
vehicle_command.param3 = math::degrees(_angle_outputs[2] + math::radians(_parameters.mnt_off_yaw));
|
||||
|
@ -238,4 +238,4 @@ void OutputMavlinkV2::_publish_gimbal_device_set_attitude()
|
|||
_gimbal_device_set_attitude_pub.publish(set_attitude);
|
||||
}
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -43,7 +43,7 @@
|
|||
#include <uORB/topics/gimbal_device_attitude_status.h>
|
||||
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
class OutputMavlinkV1 : public OutputBase
|
||||
{
|
||||
|
@ -86,4 +86,4 @@ private:
|
|||
bool _gimbal_device_found {false};
|
||||
};
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -40,7 +40,7 @@
|
|||
|
||||
using math::constrain;
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
OutputRC::OutputRC(const Parameters ¶meters)
|
||||
|
@ -109,4 +109,4 @@ void OutputRC::_stream_device_attitude_status()
|
|||
_attitude_status_pub.publish(attitude_status);
|
||||
}
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -40,7 +40,7 @@
|
|||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/gimbal_device_attitude_status.h>
|
||||
|
||||
namespace vmount
|
||||
namespace gimbal
|
||||
{
|
||||
|
||||
class OutputRC : public OutputBase
|
||||
|
@ -62,4 +62,4 @@ private:
|
|||
bool _retract_gimbal = true;
|
||||
};
|
||||
|
||||
} /* namespace vmount */
|
||||
} /* namespace gimbal */
|
|
@ -1,5 +0,0 @@
|
|||
menuconfig MODULES_VMOUNT
|
||||
bool "vmount"
|
||||
default n
|
||||
---help---
|
||||
Enable support for vmount
|
Loading…
Reference in New Issue