Skip to content

Commit 39ac45a

Browse files
topaz-244peterbarker
topaz-244
authored andcommitted
Copter: Throw mode add params for desired ascent alt after throw
1 parent 77b9800 commit 39ac45a

File tree

3 files changed

+23
-4
lines changed

3 files changed

+23
-4
lines changed

ArduCopter/Parameters.cpp

+14
Original file line numberDiff line numberDiff line change
@@ -648,6 +648,20 @@ const AP_Param::Info Copter::var_info[] = {
648648
// @Units: m
649649
// @User: Advanced
650650
GSCALAR(throw_altitude_max, "THROW_ALT_MAX", 0),
651+
652+
// @Param: THROW_ALT_DCSND
653+
// @DisplayName: Throw mode target altitude to descend
654+
// @Description: Target altitude to descend during a drop, (must be positive). This allows for rapidly clearing surrounding obstacles.
655+
// @Units: m
656+
// @User: Advanced
657+
GSCALAR(throw_altitude_descend, "THROW_ALT_DCSND", 1.0),
658+
659+
// @Param: THROW_ALT_ACSND
660+
// @DisplayName: Throw mode target altitude to ascsend
661+
// @Description: Target altitude to ascend during a throw upwards (must be positive). This allows for rapidly clearing surrounding obstacles.
662+
// @Units: m
663+
// @User: Advanced
664+
GSCALAR(throw_altitude_ascend, "THROW_ALT_ACSND", 3.0),
651665
#endif
652666

653667
#if OSD_ENABLED || OSD_PARAM_ENABLED

ArduCopter/Parameters.h

+5
Original file line numberDiff line numberDiff line change
@@ -382,6 +382,8 @@ class Parameters {
382382
k_param_throw_altitude_min,
383383
k_param_throw_altitude_max,
384384
k_param__gcs,
385+
k_param_throw_altitude_descend,
386+
k_param_throw_altitude_ascend,
385387

386388
// the k_param_* space is 9-bits in size
387389
// 511: reserved
@@ -458,6 +460,9 @@ class Parameters {
458460
AP_Enum<ModeThrow::PreThrowMotorState> throw_motor_start;
459461
AP_Int16 throw_altitude_min; // minimum altitude in m above which a throw can be detected
460462
AP_Int16 throw_altitude_max; // maximum altitude in m below which a throw can be detected
463+
464+
AP_Float throw_altitude_descend; // target altitude (meters) to descend during a drop, (must be positive)
465+
AP_Float throw_altitude_ascend; // target altitude (meters) to ascend during a throw upwards, (must be positive)
461466
#endif
462467

463468
AP_Int16 rc_speed; // speed of fast RC Channels in Hz

ArduCopter/mode_throw.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -69,12 +69,12 @@ void ModeThrow::run()
6969
// initialise the z controller
7070
pos_control->init_U_controller_no_descent();
7171

72-
// initialise the demanded height to 3m above the throw height
73-
// we want to rapidly clear surrounding obstacles
72+
// initialise the demanded height below/above the throw height from user parameters
73+
// this allows for rapidly clearing surrounding obstacles
7474
if (g2.throw_type == ThrowType::Drop) {
75-
pos_control->set_pos_desired_U_cm(inertial_nav.get_position_z_up_cm() - 100);
75+
pos_control->set_pos_desired_U_cm(inertial_nav.get_position_z_up_cm() - g.throw_altitude_descend * 100.0f);
7676
} else {
77-
pos_control->set_pos_desired_U_cm(inertial_nav.get_position_z_up_cm() + 300);
77+
pos_control->set_pos_desired_U_cm(inertial_nav.get_position_z_up_cm() + g.throw_altitude_ascend * 100.0f);
7878
}
7979

8080
// Set the auto_arm status to true to avoid a possible automatic disarm caused by selection of an auto mode with throttle at minimum

0 commit comments

Comments
 (0)