-
Notifications
You must be signed in to change notification settings - Fork 13.6k
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
Conversation
Hi @baumanta So far what I have from you:
Had any thoughts on documenting this? Essentially we want to cover:
A bunch of questions:
|
I'll try to answer your questions one by one:
|
//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 |
There was a problem hiding this comment.
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.
There was a problem hiding this comment.
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
There was a problem hiding this comment.
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
There was a problem hiding this comment.
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.
There was a problem hiding this comment.
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.
There was a problem hiding this comment.
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"); |
There was a problem hiding this comment.
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.
There was a problem hiding this comment.
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.
There was a problem hiding this comment.
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?
There was a problem hiding this comment.
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?
There was a problem hiding this comment.
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;} |
There was a problem hiding this comment.
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?
There was a problem hiding this comment.
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.
There was a problem hiding this comment.
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 |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Comment is incorrect.
Regarding the |
*/ | ||
PARAM_DEFINE_INT32(MPC_COL_AVOID, 0); | ||
/** | ||
* Minimum Obstacle Distance at which the vehicle should not get closer |
There was a problem hiding this comment.
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. |
There was a problem hiding this comment.
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 |
There was a problem hiding this comment.
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
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 guess if the companion knows its speed then you could dynamically tune this. |
You refer to local_planner a few times. What is that? Is it part of PX4? Can anyone use it on any system? |
I think this answer assumes I am talking about some specific hardware you are testing on. I am not. 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.
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. |
Well what about "Collision Prevention", "Collision Failsafe", Obstacle Geofence @mhkabir Any other better names? |
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. |
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. |
@dagar, @kabir, @hamishwillee |
There was a problem hiding this 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
@MaEtUgR What do you think about having obstacle avoidance live in it's own module and FlightTasks only subscribing to the |
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. |
@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. |
@hamishwillee this requires more work as mentioned here PX4/PX4-user_guide#375 (comment). |
@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. |
This needs a rebase. |
* @boolean | ||
* @group Multicopter Position Control | ||
*/ | ||
PARAM_DEFINE_INT32(MPC_COL_PREV, 0); |
There was a problem hiding this comment.
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.
70a6660
to
2c9d37f
Compare
Tested on pixhawk 4 and 4 mini, no issues. Pixhawk 4 mini. |
@dagar whats up with appveyor here? |
Looks like that build got stuck somewhere and exceeded its 60min maximum runtime quota, I went ahead and triggered a rebuild of this PR |
Appveyor ✅ |
void CollisionPrevention::reset_constraints() | ||
{ | ||
|
||
_move_constraints_x_normalized(0) = 0.0f; //normalized constraint in negative x-direction |
There was a problem hiding this comment.
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; |
There was a problem hiding this comment.
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
@dagar is there anything else that needs fixing? If not, could we merge it? |
@baumanta please rebase and then lets get this merged. Everyone seems to be happy now |
0c08685
to
2043246
Compare
There was a problem hiding this 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"); |
There was a problem hiding this comment.
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; |
There was a problem hiding this comment.
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); |
There was a problem hiding this comment.
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); |
There was a problem hiding this comment.
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) |
There was a problem hiding this comment.
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(); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
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++) { |
There was a problem hiding this comment.
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); |
There was a problem hiding this comment.
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)); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
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; |
There was a problem hiding this comment.
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.
There was a problem hiding this 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 |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
* 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 |
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.