From 27dc60a41953015650044d04c989e8b2cd9725a6 Mon Sep 17 00:00:00 2001 From: baumanta Date: Mon, 5 Nov 2018 08:42:30 +0100 Subject: [PATCH] Improve comments --- src/lib/CollisionAvoidance/CollisionAvoidance.cpp | 2 +- src/modules/mc_pos_control/mc_pos_control_params.c | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/lib/CollisionAvoidance/CollisionAvoidance.cpp b/src/lib/CollisionAvoidance/CollisionAvoidance.cpp index 823719c0c3..7122865792 100644 --- a/src/lib/CollisionAvoidance/CollisionAvoidance.cpp +++ b/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)); 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; diff --git a/src/modules/mc_pos_control/mc_pos_control_params.c b/src/modules/mc_pos_control/mc_pos_control_params.c index b09af23e3b..6d9e8ad1ac 100644 --- a/src/modules/mc_pos_control/mc_pos_control_params.c +++ b/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); /** - * 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 * @group Multicopter Position Control */ 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 * @max 15