Get_vector_perpendicular requires vec_neu?

Howdy all,
In AP_Avoidance.cpp, line 610, the get_vector_perpendicular function is defined. This function requires two inputs; obstacle (makes sense, we are trying to avoid an obstacle), and vec_neu. But, vec_neu is only created after the function get_vector_perpendicular is called, so how is a self referencing function valid? Is vec_neu created somewhere else? What is the value of vec_neu on the first run through of the code?
Thanks for all the help!

Also curious: I don’t think that the value of vec_neu is ever actually used in the function, it is just redefined. So is it possible that it’s unnecessary for the function?

HI @skybound
I hope I understood your question correctly.
So AP_Avoidance::get_vector_perpendicular is defined at AP_Avoidance.cpp but actually used in avoidance_adsb.cpp.
Throughout the code base you will see that mostly all vectors are passed by “reference” to any function rather than directly passing it…
We do this because passing directly would make a copy of that vector inside the function, which is a little inefficient.
Passing by reference gets around this problem! Also you can change the value of the passed variable from where ever it was defined by doing this.

“What is the value of vec_neu on the first run through of the code?” - I am not sure I understand this bit correctly … But all Vector types are initialized as “zero” vectors by default (unless they were initialized with some other value)

Sorry if any of the information was wrong here… This is to the best of my abilities!

1 Like

Hi @rishabsingh3003,
I think you understood me perfectly! Thank you so much for your reply!
So I think I understand the concept of pass-by-reference, but the avoidance_adsb.cpp is interesting. I have a few questions:

  1. Even though vec_neu is a pass-by-reference, it still to my eye looks like whatever is passed into it is never used by the function get_vector_perpendicular, it only seems to use the values from the obstacle data passed into it. So I guess I’m missing something here. What I meant by my first question was that when ArduPilot first runs through the Avoidance logic, vec_neu has yet to be created, because it has yet to run the function get_vector_perpendicular. So before vec_neu is created, what value is given to the function? Is it a zero vector?

  2. I took a look at avoidance_adsb.cpp. It looks like when get_vector+perpendicular is called by, for example handle_avoidance_horizontal, that it creates the class Vector3f velocity_neu, but then it seems like the function creates a destination to fly to using the set target plane.guided_WP_loc.offset(velocity_neu.x, velocity_neu.y);. So does get_vector_perpendicular create a velocity vector for ArduPilot to change it’s speed with, or does it create a destination target for ArduPilot to fly to?

  3. How does ArduPilot decide to use either a horizontal, vertical, or perpendicular avoidance maneuver?

Thank you again for your reply, it was a huge help and got me thinking about new ideas!

If I could bother you once more @rishabsingh3003, can you help me understand the function update_threat_level? I know that this function basically decides how to handle a threat based on it’s threat level, determined by the closest approach. How that works is what I’m confused about:

  1. What is the relationship between MAV_COLLISION_ACTION and MAV_COLLISION_THREAT_LEVEL? I know that these must be very closely related. Because it looks like the mav collision threat level is defined first, I think that the action must be based on the threat level. Also, it would make logical sense, as you cant decide an action if you don’t know what you’re dealing with. But where does the action get decided?

  2. I know that the MAV_COLLISION_ACTION and the MAV_COLLISION_THREAT_LEVEL are enumerations defined in common.h, but I don’t understand the relationship between the two.

  3. I am having specific trouble with this line (AP_Avoidance.cpp, line 540): action = (MAV_COLLISION_ACTION)_fail_action.get(). I know that this is just defining the action to be whatever the mav collision action is equal to using the get() function, but I don’t understand what _fail_action does. It looks like it’s a parameter, but what does it do? I’m assuming its what the user tells ArduPilot to do when a threat has reached threat_level = high, or when an obstacle is inside the failsafe radius, but it’s only defined once on AP_Avoidance.h line 196, and it’s not clear to me how it’s used. Why couldn’t you just say MAV_COLLISION_ACTION.get()?

  4. This is a bit unrelated, but I found it when exploring the avoidance logic a bit more. I found this function: get_destination_perpendicular, but I don’t see it used anywhere. It’s declared as a function in AP_Avoidance.h, line 136, but the function is never actually defined from what I can see. What’s going on here?

Thank you again a million times over for looking at my questions!