From d8164377a820f63d9e68b4e397d2b03e00c84b11 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 7 Jan 2018 22:59:31 +0100 Subject: [PATCH] Navigator: Move mission param into mission params This is important for the compile scope. --- src/drivers/vmount/vmount_params.c | 14 -------------- src/modules/navigator/mission.cpp | 3 ++- src/modules/navigator/mission_params.c | 14 ++++++++++++++ 3 files changed, 16 insertions(+), 15 deletions(-) diff --git a/src/drivers/vmount/vmount_params.c b/src/drivers/vmount/vmount_params.c index 8c97372cd3..4562e69558 100644 --- a/src/drivers/vmount/vmount_params.c +++ b/src/drivers/vmount/vmount_params.c @@ -225,17 +225,3 @@ PARAM_DEFINE_FLOAT(MNT_OFF_ROLL, 0.0f); * @group Mount */ PARAM_DEFINE_FLOAT(MNT_OFF_YAW, 0.0f); - -/** -* Enable yaw control of the mount. (Only affects multicopters and ROI mission items) -* -* If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading mode as specified by MIS_YAWMODE. -* If disabled, the vehicle will yaw towards the ROI. -* -* @value 0 Disable -* @value 1 Enable -* @min 0 -* @max 1 -* @group Mount -*/ -PARAM_DEFINE_INT32(MNT_YAW_CTL, 0); diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index fe7145b39a..c1ed9a0820 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -64,7 +64,8 @@ Mission::Mission(Navigator *navigator, const char *name) : _param_dist_1wp(this, "MIS_DIST_1WP", false), _param_dist_between_wps(this, "MIS_DIST_WPS", false), _param_altmode(this, "MIS_ALTMODE", false), - _param_yawmode(this, "MIS_YAWMODE", false) + _param_yawmode(this, "MIS_YAWMODE", false), + _param_mnt_yaw_ctl(this, "MIS_MNT_YAW_CTL", false) { } diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c index 4892e33e3a..7d117f723a 100644 --- a/src/modules/navigator/mission_params.c +++ b/src/modules/navigator/mission_params.c @@ -134,6 +134,20 @@ PARAM_DEFINE_INT32(MIS_ALTMODE, 1); */ PARAM_DEFINE_INT32(MIS_YAWMODE, 1); +/** +* Enable yaw control of the mount. (Only affects multicopters and ROI mission items) +* +* If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading mode as specified by MIS_YAWMODE. +* If disabled, the vehicle will yaw towards the ROI. +* +* @value 0 Disable +* @value 1 Enable +* @min 0 +* @max 1 +* @group Mission +*/ +PARAM_DEFINE_INT32(MIS_MNT_YAW_CTL, 0); + /** * Time in seconds we wait on reaching target heading at a waypoint if it is forced. *