aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mc_pos_control_multiplatform
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-02-22 13:02:22 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-02-24 20:33:32 +0100
commita56c16dfab948517007ad570d67f02dd4e2edb60 (patch)
tree724c2534edbbaba37271a3edc63248baa558fe9d /src/modules/mc_pos_control_multiplatform
parentf1c6b24f7a80f88baf272bc0b947f7e9649bee27 (diff)
downloadpx4-firmware-a56c16dfab948517007ad570d67f02dd4e2edb60.tar.gz
px4-firmware-a56c16dfab948517007ad570d67f02dd4e2edb60.tar.bz2
px4-firmware-a56c16dfab948517007ad570d67f02dd4e2edb60.zip
multiplatform port of #1741: move params from att control to pos control
Diffstat (limited to 'src/modules/mc_pos_control_multiplatform')
-rw-r--r--src/modules/mc_pos_control_multiplatform/mc_pos_control.cpp10
-rw-r--r--src/modules/mc_pos_control_multiplatform/mc_pos_control.h6
-rw-r--r--src/modules/mc_pos_control_multiplatform/mc_pos_control_params.c29
-rw-r--r--src/modules/mc_pos_control_multiplatform/mc_pos_control_params.h3
4 files changed, 47 insertions, 1 deletions
diff --git a/src/modules/mc_pos_control_multiplatform/mc_pos_control.cpp b/src/modules/mc_pos_control_multiplatform/mc_pos_control.cpp
index 1fe75b90c..1c0298a07 100644
--- a/src/modules/mc_pos_control_multiplatform/mc_pos_control.cpp
+++ b/src/modules/mc_pos_control_multiplatform/mc_pos_control.cpp
@@ -82,7 +82,10 @@ MulticopterPositionControl::MulticopterPositionControl() :
.xy_ff = px4::ParameterFloat("MPC_XY_FF", PARAM_MPC_XY_FF_DEFAULT),
.tilt_max_air = px4::ParameterFloat("MPC_TILTMAX_AIR", PARAM_MPC_TILTMAX_AIR_DEFAULT),
.land_speed = px4::ParameterFloat("MPC_LAND_SPEED", PARAM_MPC_LAND_SPEED_DEFAULT),
- .tilt_max_land = px4::ParameterFloat("MPC_TILTMAX_LND", PARAM_MPC_TILTMAX_LND_DEFAULT)
+ .tilt_max_land = px4::ParameterFloat("MPC_TILTMAX_LND", PARAM_MPC_TILTMAX_LND_DEFAULT),
+ .man_roll_max = px4::ParameterFloat("MC_MAN_R_MAX", PARAM_MPC_MAN_R_MAX_DEFAULT),
+ .man_pitch_max = px4::ParameterFloat("MC_MAN_P_MAX", PARAM_MPC_MAN_P_MAX_DEFAULT),
+ .man_yaw_max = px4::ParameterFloat("MC_MAN_Y_MAX", PARAM_MPC_MAN_Y_MAX_DEFAULT)
}),
_ref_alt(0.0f),
_ref_timestamp(0),
@@ -146,6 +149,11 @@ MulticopterPositionControl::parameters_update()
_params.land_speed = _params_handles.land_speed.update();
_params.tilt_max_land = math::radians(_params_handles.tilt_max_land.update());
+ /* manual control scale */
+ _params.man_roll_max = math::radians(_params_handles.man_roll_max.update());
+ _params.man_pitch_max = math::radians(_params_handles.man_pitch_max.update());
+ _params.man_yaw_max = math::radians(_params_handles.man_yaw_max.update());
+
_params.pos_p(0) = _params.pos_p(1) = _params_handles.xy_p.update();
_params.pos_p(2) = _params_handles.z_p.update();
_params.vel_p(0) = _params.vel_p(1) = _params_handles.xy_vel_p.update();
diff --git a/src/modules/mc_pos_control_multiplatform/mc_pos_control.h b/src/modules/mc_pos_control_multiplatform/mc_pos_control.h
index b754ccf01..59b663b9f 100644
--- a/src/modules/mc_pos_control_multiplatform/mc_pos_control.h
+++ b/src/modules/mc_pos_control_multiplatform/mc_pos_control.h
@@ -126,6 +126,9 @@ protected:
px4::ParameterFloat tilt_max_air;
px4::ParameterFloat land_speed;
px4::ParameterFloat tilt_max_land;
+ px4::ParameterFloat man_roll_max;
+ px4::ParameterFloat man_pitch_max;
+ px4::ParameterFloat man_yaw_max;
} _params_handles; /**< handles for interesting parameters */
struct {
@@ -134,6 +137,9 @@ protected:
float tilt_max_air;
float land_speed;
float tilt_max_land;
+ float man_roll_max;
+ float man_pitch_max;
+ float man_yaw_max;
math::Vector<3> pos_p;
math::Vector<3> vel_p;
diff --git a/src/modules/mc_pos_control_multiplatform/mc_pos_control_params.c b/src/modules/mc_pos_control_multiplatform/mc_pos_control_params.c
index c741a7f0a..709085662 100644
--- a/src/modules/mc_pos_control_multiplatform/mc_pos_control_params.c
+++ b/src/modules/mc_pos_control_multiplatform/mc_pos_control_params.c
@@ -210,3 +210,32 @@ PX4_PARAM_DEFINE_FLOAT(MPC_TILTMAX_LND);
*/
PX4_PARAM_DEFINE_FLOAT(MPC_LAND_SPEED);
+/**
+ * Max manual roll
+ *
+ * @unit deg
+ * @min 0.0
+ * @max 90.0
+ * @group Multicopter Attitude Control
+ */
+PX4_PARAM_DEFINE_FLOAT(MPC_MAN_R_MAX);
+
+/**
+ * Max manual pitch
+ *
+ * @unit deg
+ * @min 0.0
+ * @max 90.0
+ * @group Multicopter Attitude Control
+ */
+PX4_PARAM_DEFINE_FLOAT(MPC_MAN_P_MAX);
+
+/**
+ * Max manual yaw rate
+ *
+ * @unit deg/s
+ * @min 0.0
+ * @group Multicopter Attitude Control
+ */
+PX4_PARAM_DEFINE_FLOAT(MPC_MAN_Y_MAX);
+
diff --git a/src/modules/mc_pos_control_multiplatform/mc_pos_control_params.h b/src/modules/mc_pos_control_multiplatform/mc_pos_control_params.h
index fec3bcb7c..8c8b707ae 100644
--- a/src/modules/mc_pos_control_multiplatform/mc_pos_control_params.h
+++ b/src/modules/mc_pos_control_multiplatform/mc_pos_control_params.h
@@ -58,4 +58,7 @@
#define PARAM_MPC_TILTMAX_AIR_DEFAULT 45.0f
#define PARAM_MPC_TILTMAX_LND_DEFAULT 15.0f
#define PARAM_MPC_LAND_SPEED_DEFAULT 1.0f
+#define PARAM_MPC_MAN_R_MAX_DEFAULT 35.0f
+#define PARAM_MPC_MAN_P_MAX_DEFAULT 35.0f
+#define PARAM_MPC_MAN_Y_MAX_DEFAULT 120.0f