Browse Source

Improve comments

sbg
baumanta 6 years ago committed by Beat Küng
parent
commit
27dc60a419
  1. 2
      src/lib/CollisionAvoidance/CollisionAvoidance.cpp
  2. 6
      src/modules/mc_pos_control/mc_pos_control_params.c

2
src/lib/CollisionAvoidance/CollisionAvoidance.cpp

@ -165,7 +165,7 @@ void CollisionAvoidance::modifySetpoint(Vector2f &original_setpoint, const float
|| new_setpoint(1) > 1.05f * original_setpoint(1)); || new_setpoint(1) > 1.05f * original_setpoint(1));
if (currently_interfering && (currently_interfering != _interfering)) { if (currently_interfering && (currently_interfering != _interfering)) {
mavlink_log_critical(&_mavlink_log_pub, "Collision Avoidance starts interfering"); mavlink_log_critical(&_mavlink_log_pub, "Collision Warning");
} }
_interfering = currently_interfering; _interfering = currently_interfering;

6
src/modules/mc_pos_control/mc_pos_control_params.c

@ -739,16 +739,16 @@ PARAM_DEFINE_INT32(MPC_OBS_AVOID, 0);
PARAM_DEFINE_INT32(MPC_YAW_MODE, 0); PARAM_DEFINE_INT32(MPC_YAW_MODE, 0);
/** /**
* Flag to enable the use of a range sensor for collision avoidance. * Flag to enable the use of a MAVLink range sensor for collision avoidance.
* *
* @boolean * @boolean
* @group Multicopter Position Control * @group Multicopter Position Control
*/ */
PARAM_DEFINE_INT32(MPC_COL_AVOID, 0); PARAM_DEFINE_INT32(MPC_COL_AVOID, 0);
/** /**
* Minimum Obstacle Distance at which the vehicle should not get closer * Minimum distance the vehicle should keep to all obstacles
* *
* Only relevant if in Position control and the range sensor is active * Only used in Position mode when collision avoidance is active (see MPC_COL_AVOID).
* *
* @min 0 * @min 0
* @max 15 * @max 15

Loading…
Cancel
Save