Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add a collision avoidance library which uses range data #10785

Merged
merged 10 commits into from
Nov 20, 2018

Conversation

baumanta
Copy link
Contributor

@baumanta baumanta commented Oct 30, 2018

Refactoring from PR #10710

Put collision avoidance into a library

Added checks to discard old data. Added notifications for user if collision avoidance is interfering. Added warnings if no range data is received.

@hamishwillee
Copy link
Contributor

Hi @baumanta

So far what I have from you:

This library uses LaserScan data. This can either come from a laser scanner or the Obstacle avoidance on the companion is also able to provide the data. This Collision avoidance is not exactly an obstacle avoidance. It does not aim at finding a path around obstacles. But rather brake if something is too close. It is usable right now in Manual Position control only.

Had any thoughts on documenting this? Essentially we want to cover:

  • What it is/does
  • How it is enabled - what software and hardware you need, and how to use it
  • Any constraints

A bunch of questions:

  • How is this enabled? Is it always on all the time if there is a data source or is there a parameter to turn it on and off.
  • My assumptions are that
    • information about the obstacle always comes to PX via the OBSTACLE_DISTANCE message - is that correct? (ie there is no PX driver and direct hardware attachment support?)
    • The system doesn't care how the OBSTACLE_DISTANCE is generated - via a LaserScan or from some sort of "map" produced by another mechanism?
  • What is the required OBSTACLE_DISTANCE message send rate from source system
  • Are there any other messages associated with this system?
    • I assume that COLLISION is not used in any way by this system?
  • What parameters/tuning is available?
    • Along those lines, I'm expecting that you'll have a tunable algorithm to calculate the breaking based on current speed and distance to target, and some settings that define things like how close you will allow the vehicle to get, and maybe the breaking curve as a function of some speed and distance (either way, we should explain what people will see as the vehicle comes to collide - long slow decrease in speed trending to X cm gap, or quick break at X m to target ... or whatever)
  • Are any responses other than stopping supported? What happens then? - ie is this a permanent invisible barrier - can they move sideways?
  • Does the system notify anything else of the collision - e.g. QGC? If so, what messages does it send?
  • If using a LaserScan:
    • How is it connected?
    • What models have been used/can be used
    • How generate the OBSTACLE_DISTANCE stream from whatever model is used
    • What software do you need on the companion (assuming that is used) and how is it set up.
  • If using data from another source (e.g. obstacle avoidance) how is that configured/setup?
  • What happens if someone is using both obstacle and collision avoidance.
  • Can we rename - the avoidance makes this too similar to obstacle avoidance. While the name is technically correct, most people associate avoidance with a "movement" away from something causing a collision, and we're not doing that. Options include "Collision Prevention", "Collision Failsafe".

@baumanta
Copy link
Contributor Author

baumanta commented Nov 2, 2018

Hi @hamishwillee

I'll try to answer your questions one by one:

  • There are 2 parameters belonging to the collision avoidance. It is enabled by setting MPC_COL_AVOID = 1 and disabled by setting it to zero. The parameter MPC_COL_AVOID_D specifies the distance it tries to keep to any obstacle.
  • You are right, data comes in over the OBSTACLE_DISTANCE message. This message is an array of angular distance measurments. It can either come directly form a range sensor or it can be generated by the local_planner. To enable the generation in the local_planner the parameter send_obstacles_fuc_ in the planner has to be set to TRUE. The collision avoidance makes no difference regarding the source of the message.
  • We have not specified a minimum rate. If the collision avoidance is enables and it gets stale (older than 0.5s) or no data it will output a warning in QGC. So if the rate is lower than 2Hz you will get warnings. But this threshold is up for discussion, also as it depends on the maximum velocity.
  • There are no other messages. It take OBSTACLE_DISTANCE and from that knowledge computes an adaption to the velocity setpoint.
  • As already mentioned, there is the parameter MPC_COL_AVOID_D which specifies the closest distance to any obstacle. The vehicle will start reduciing speed as soon as any obstacle comes in its field of view. and beaks linearly such that the velocity setpoint will have no component towards the obstacle anymore once the specified distance to it is reached. If it gets closer, it will be repelled.
  • Yes, all RC inputs are executed except for the ones bringing the drone closer to the obstacle. So if you press forward and slightly left. It will slowdown and, as soon as the min distance is reached, drift around the obstacle to the left until the forward component can be executed again.
  • It sends a warning to GCQ that says something along the lines : "Collision avoidance starts interfering". This message is only sent when in the last timestep the velocity setpoint was not modified and now it is.
  • We did not test it using a range sensor. I do not know how you would integrate that and if a conversion is needed to fit the data into the OBSTACLE_DISTANCE message. But as a range sensor is a rather common sensor I would expect a plugin to be available. If you use the companion, you need to set up the local_planner and set the parameter send_obstacles_fuc_ = TRUE.
  • Right now it is not possible to use both. Obstacle avoidance only works in offboard and mission, whereas collision avoidance only work in position mode. This would need further testing.
  • I'm open to any suggestions regarding the name of the feature. I agree that this might be confusing.

//determine if distance bin is valid and contains a valid distance measurement
if (_obstacle_distance.distances[i] < _obstacle_distance.max_distance &&
_obstacle_distance.distances[i] > _obstacle_distance.min_distance && i * _obstacle_distance.increment < 360) {
float distance = _obstacle_distance.distances[i] / 100.0f; //convert to meters
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This needs to be compensated for the tilt of the vehicle.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think so. The _obstacle_distances are in local_origin frame which is stationary and independent on the tilt

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't agree. The definition suggests that it's in the sensor frame, which also makes sense. https://github.com/PX4/Firmware/blob/master/msg/obstacle_distance.msg#L10

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Almost any distance sensor (e.g single sonar, or planar laser scanner, whatever) will have readings in its body frame.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The message is in local frame. See https://mavlink.io/en/messages/common.html#OBSTACLE_DISTANCE .
On the Fimware the description never got updated (#9071) and I don't have merging rights.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Furthermore, on the avoidance side we are keeping memory of the obstacles. That was one of the main reasons why we choose to have distances in local frame

|| new_setpoint(1) > 1.05f * original_setpoint(1));

if (currently_interfering && (currently_interfering != _interfering)) {
mavlink_log_critical(&_mavlink_log_pub, "Collision Avoidance starts interfering");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok for debugging, but should be removed before merge. We need better user feedback than this.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We would like to have it in. It is very useful for the user to get a notification once the drone does not execute the RC input anymore as the user would expect. If you press forward and slightly left the drone will only go left if it detected an obstacle to the front, which can be pretty counter intuitive if it does that without notifying you.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This notification is confusing and doesn't really tell the user much. OK for developers, but a "standard" user has no idea what "Collision Avoidance starts interfering" means.

@dagar Do you know what DJI does?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@baumanta What @mhkabir is saying is that some notification is needed, but that this particular text could be improved.

@mhkabir @dagar Based purely on this post I think that DJI do a beeps with pitch/frequency based on proximity. To me that seems very familiar from car reversing sensor systems - and it would be really good if we could have similar - both QGC and on transmitter (ie via FrSky telemetry). Is this possible?
I'd also quite like a visual indicator.

Complementary text also fine. For this, what if we just used text: "Collision warning"?

A specific message for this notification probably needed?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We plan on improving the notifications, e.g. with a visualization in QGC which shows blocked sector as it is done in cars. @mrivi uses that already for yuneec. But we do not have the capactity to do that right now, so we will stick to the message in the mean time. If you have any suggestions for improving the message, I'll be glad to change it of course.

/**
* Sets an external collision avoidance which can be used to modify setpoints
*/
void setCollisionAvoidance(CollisionAvoidance *ext_collision_avoidance) override {_ext_collision_avoidance = ext_collision_avoidance;}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What does "sets an external collision avoidance" mean here?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I implemented the library analog to the weather vane library which was recently merged. It is integrated in exactly the same way. In that code the instance was referred to as an "external yaw handler". That was why I also used the term external. But if you have a suggestion to clarify the comment, I'd be glad to improve it.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

My question is - what does "Sets" mean? What is being "set"?

// activate the collision avoidance if required. If activated a flighttask can use it modify the setpoint
if (_ca_controller != nullptr) {

// in manual mode we just want to use weathervane if position is controlled as well
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Comment is incorrect.

@mhkabir
Copy link
Member

mhkabir commented Nov 2, 2018

Regarding the collision_constraints topic, we should check how this plays with the EKF velocity constraints.

*/
PARAM_DEFINE_INT32(MPC_COL_AVOID, 0);
/**
* Minimum Obstacle Distance at which the vehicle should not get closer
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

"Obstacle Distance" above are not proper nouns, so should not be capitalised.

Maybe change to:

Minimum allowed target obstacle distance

@@ -682,3 +682,22 @@ PARAM_DEFINE_INT32(MPC_OBS_AVOID, 0);
* @group Mission
*/
PARAM_DEFINE_INT32(MPC_YAW_MODE, 0);

/**
* Flag to enable the use of a range sensor for collision avoidance.
Copy link
Contributor

@hamishwillee hamishwillee Nov 4, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Range sensor or "MAVLink range sensor"?

The problem here is that there is a reasonable assumption that a flight controller based sensor might work.

So perhaps:

Enable the use of a MAVLink range sensor for collision avoidance.

/**
* Minimum Obstacle Distance at which the vehicle should not get closer
*
* Only relevant if in Position control and the range sensor is active
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Perhaps

Only used in Position mode when collision avoidance is active (see MPC_COL_AVOID).

Perhaps

@hamishwillee
Copy link
Contributor

hamishwillee commented Nov 5, 2018

We have not specified a minimum rate. If the collision avoidance is enables and it gets stale (older than 0.5s) or no data it will output a warning in QGC. So if the rate is lower than 2Hz you will get warnings. But this threshold is up for discussion, also as it depends on the maximum velocity.

Have we done any profiling? What should we recommend? What are we using now?

At 20ish metres/second (a non-racer quad at high speed) with a 10m rangefinder you would need more than 2 Hz just to guarantee seeing the message.
I presume that the velocity reduction is independent of the rate of message receipt (ie speed reduction calculated every time a message is received, but will proceed to zero velocity based on initial message if no other is received)?

I guess if the companion knows its speed then you could dynamically tune this.

@hamishwillee
Copy link
Contributor

You refer to local_planner a few times. What is that? Is it part of PX4? Can anyone use it on any system?

@hamishwillee
Copy link
Contributor

We did not test it using a range sensor. But as a range sensor is a rather common sensor I would expect a plugin to be available. If you use the companion, you need to set up the local_planner and set the parameter send_obstacles_fuc_ = TRUE.

I think this answer assumes I am talking about some specific hardware you are testing on. I am not.
I am talking about a vanilla PX4 firmware build running on a Pixhawk series flight controller with a rangefinder attached.

For obstacle avoidance or any system that needs to build a map of the the obstacle then yes, you need a companion to do the calculations. But this is not a complex calculation - you can do this without a companion.

I do not know how you would integrate that and if a conversion is needed to fit the data into the OBSTACLE_DISTANCE message.

Me either, but I suspect creating a fairly basic form would be easy enough.

YOu would need a parameter to specify the source - external mavlink message or internal distance sensor, and monitor for the distance_message topic.

Each distance_message only has one distance rather than an array and the orientation is provided. So you could build the array, but more likely you'd just use the ROTATION_FORWARD_FACING sensor, if set.

Anyway, just my two bits.

@hamishwillee
Copy link
Contributor

I'm open to any suggestions regarding the name of the feature. I agree that this might be confusing.

Well what about "Collision Prevention", "Collision Failsafe", Obstacle Geofence

@mhkabir Any other better names?

@hamishwillee
Copy link
Contributor

Right now it is not possible to use both. Obstacle avoidance only works in offboard and mission, whereas collision avoidance only work in position mode. This would need further testing.

Thank you. I realised that it was a dumb question - they are mutually exclusive. You use obstacle avoidance in automatic modes because you know where you want to go, and can hence plot a path to a destination. Collision avoidance is used in manual modes where the system doesn't know where you ultimately want to go.

@baumanta
Copy link
Contributor Author

baumanta commented Nov 5, 2018

You refer to local_planner a few times. What is that? Is it part of PX4? Can anyone use it on any system?

The local planner is one of the algorithms in the avoidance package. Anyone can use it, provided he has the required hardware (companion computer, cameras, pixhawk, ...). The exact requirements are still under discussion.

@baumanta
Copy link
Contributor Author

baumanta commented Nov 5, 2018

@dagar, @kabir, @hamishwillee
As I understand from the discussion, the only open issue is the name of this feature. I agree that collision avoidance might be to close to obstacle avoidance.
Suggestions for new name so far are: "Collision Prevention", "Collision Failsafe", "Obstacle Geofence"
I would be glad if we could decide soon, such that this PR can be merged

MaEtUgR
MaEtUgR previously requested changes Nov 5, 2018
Copy link
Member

@MaEtUgR MaEtUgR left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why is there a dynamically allocated external _ca_controller with update and even logic in mc_pos_control module? It gets passed into every FlightTask as ext_collision_avoidance pointer to only be used in FlightTaskManualPosition.

Could we make it far less complicated by only allocating on stack and updating in the tasks that use it by now? For the _obstacle_distance subscription I would pass the subscription_array from the task into the library and get the data directly. Then you also have no problem with resubscribing because the array keeps everything for you.

EDIT: see example #10809

src/modules/mc_pos_control/mc_pos_control_main.cpp Outdated Show resolved Hide resolved
src/modules/mc_pos_control/mc_pos_control_main.cpp Outdated Show resolved Hide resolved
src/modules/mc_pos_control/mc_pos_control_params.c Outdated Show resolved Hide resolved
@mhkabir
Copy link
Member

mhkabir commented Nov 5, 2018

@MaEtUgR What do you think about having obstacle avoidance live in it's own module and FlightTasks only subscribing to the collision_constraints topic from it? This would avoid kludging up the position controller. I feel like having collision avoidance as a library inside the position controller isn't great from the architecture perspective.

@baumanta
Copy link
Contributor Author

baumanta commented Nov 5, 2018

@MaEtUgR What do you think about having obstacle avoidance live in it's own module and FlightTasks only subscribing to the collision_constraints topic from it? This would avoid kludging up the position controller. I feel like having collision avoidance as a library inside the position controller isn't great from the architecture perspective.

It was already decided in accordance with @dagar, @bkueng and @bresch that a library would be more suitable right now, as a module introduces too much overhead for those few lines of code.

@MaEtUgR
Copy link
Member

MaEtUgR commented Nov 5, 2018

@mhkabir a module currently has too much overhead, otherwise we could also run FlightTask in a separate module it's designed for that with uORB messages as interface.

@baumanta A library totally makes sense and the one you wrote looks good on the first glance. My comments are only about how to instantiate and how data gets in and out. Maybe I can do a quick example to reflect what I mean and help you evaluate further.

@MaEtUgR
Copy link
Member

MaEtUgR commented Nov 5, 2018

@baumanta I prepared a pr to show what I meant in my review: #10809
I hope this helps.

@mrivi
Copy link
Contributor

mrivi commented Nov 6, 2018

I'd like to see some testing with rangefinder connected to flight controller before this goes in.

@hamishwillee this requires more work as mentioned here PX4/PX4-user_guide#375 (comment).
As of now, the only way to generate a obstacle_distance message inside PX4 is through the local_planner algorithm, running on a companion computer.
All other range sensors publish their data on the distance_sensor topic which has no interface to the current CollisionAvoidance library.

@baumanta
Copy link
Contributor Author

baumanta commented Nov 6, 2018

@hamishwillee The distance sensor integration will certainly be high on our priority list. But I will not have the capacity to do that in the next two weeks. Therefore, I would be glad if we could discuss that independently in a second PR.

@MaEtUgR MaEtUgR dismissed their stale review November 13, 2018 15:02

comments were addressed

@dagar
Copy link
Member

dagar commented Nov 14, 2018

This needs a rebase.

* @boolean
* @group Multicopter Position Control
*/
PARAM_DEFINE_INT32(MPC_COL_PREV, 0);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These parameters can live in the actual collision avoidance library.

@baumanta baumanta force-pushed the collision_avoidance_library branch from 70a6660 to 2c9d37f Compare November 15, 2018 14:01
@Avysuarez
Copy link

@thomasgubler
Copy link
Contributor

@dagar whats up with appveyor here?

@mrpollo
Copy link
Contributor

mrpollo commented Nov 16, 2018

Looks like that build got stuck somewhere and exceeded its 60min maximum runtime quota, I went ahead and triggered a rebuild of this PR

@mrpollo
Copy link
Contributor

mrpollo commented Nov 16, 2018

Appveyor ✅

void CollisionPrevention::reset_constraints()
{

_move_constraints_x_normalized(0) = 0.0f; //normalized constraint in negative x-direction
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

_move_constraints_x_normalized.zero()

}

//scale the velocity reductions with the maximum possible velocity along the respective axis
_move_constraints_x(0) *= v_max_x;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These are vectors you can multiply by a single constant.

_move_constraints_x *= v_max_x

@baumanta
Copy link
Contributor Author

@dagar is there anything else that needs fixing? If not, could we merge it?

@thomasgubler
Copy link
Contributor

@baumanta please rebase and then lets get this merged. Everyone seems to be happy now

@thomasgubler
Copy link
Contributor

@bkueng could you please help getting this merged after the rebase by @baumanta?

@baumanta baumanta force-pushed the collision_avoidance_library branch from 0c08685 to 2043246 Compare November 20, 2018 08:33
Copy link
Member

@bkueng bkueng left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewed and remarked some details. Overall looks good.

@@ -633,6 +634,7 @@ void Logger::add_default_topics()
add_topic("manual_control_setpoint", 200);
add_topic("mission");
add_topic("mission_result");
add_topic("obstacle_distance");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We should add a vision/avoidance logger profile. We can do that in a next iteration though.

#include <systemlib/mavlink_log.h>
#include <lib/FlightTasks/tasks/FlightTask/SubscriptionArray.hpp>

using namespace matrix;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please remove all using namespace from the header. You can use them in the .cpp file.

* @unit meters
* @group Multicopter Position Control
*/
PARAM_DEFINE_FLOAT(MPC_COL_PREV_D, 4.0f);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If we use a negative value or 0 to disable distance-based collision avoidance, we can safe one parameter and remove MPC_COL_PREV.


void reset_constraints();

void publish_constraints(const Vector2f &original_setpoint, const Vector2f &adapted_setpoint);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please make everything private that is not or not supposed to be used from outside.



CollisionPrevention::CollisionPrevention() :
ModuleParams(nullptr)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Here you should do:

CollisionPrevention::CollisionPrevention(ModuleParams *parent) :
	ModuleParams(parent)

Then pass the FlightTaskManualPosition object to the CollisionPrevention constructor (FlightTaskManualPosition::FlightTaskManualPosition() : _collision_prevention(this)).

Then the parameters can be changed in-flight.


void CollisionPrevention::update_range_constraints()
{
obstacle_distance_s obstacle_distance = _sub_obstacle_distance->get();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
obstacle_distance_s obstacle_distance = _sub_obstacle_distance->get();
const obstacle_distance_s& obstacle_distance = _sub_obstacle_distance->get();

if (hrt_elapsed_time(&obstacle_distance.timestamp) < RANGE_STREAM_TIMEOUT_US) {
float max_detection_distance = obstacle_distance.max_distance / 100.0f; //convert to meters

for (int i = 0; i < 72; i++) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please use sizeof(obstable_distance::distances)/sizeof(obstable_distance::distances[0]) instead of 72.

if (obstacle_distance.distances[i] < obstacle_distance.max_distance &&
obstacle_distance.distances[i] > obstacle_distance.min_distance && i * obstacle_distance.increment < 360) {
float distance = obstacle_distance.distances[i] / 100.0f; //convert to meters
float angle = i * obstacle_distance.increment * (M_PI / 180.0);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Use math::radians() to convert.

_move_constraints_y = _move_constraints_y_normalized;

// calculate the maximum velocity along x,y axis when moving in the demanded direction
float vel_mag = sqrt(original_setpoint(0) * original_setpoint(0) + original_setpoint(1) * original_setpoint(1));
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
float vel_mag = sqrt(original_setpoint(0) * original_setpoint(0) + original_setpoint(1) * original_setpoint(1));
float vel_mag = original_setpoint.norm();

_move_constraints_y(1) = v_max_y - _move_constraints_y(1);

//constrain the velocity setpoint to respect the velocity limits
Vector2f new_setpoint = original_setpoint;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why do you initialize here? You overwrite it with the next lines.

Copy link
Member

@bkueng bkueng left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Merging, and fixing the typo directly.

/**
* Minimum distance the vehicle should keep to all obstacles
*
* Only used in Position mode. Collision avoidace is disable by setting this parameter to a negative value
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
* Only used in Position mode. Collision avoidace is disable by setting this parameter to a negative value
* Only used in Position mode. Collision avoidace is disabled by setting this parameter to a negative value

@bkueng bkueng merged commit 053494c into PX4:master Nov 20, 2018
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.