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

AP_RangeFinder: allow for more than 327m range #27886

Open
wants to merge 18 commits into
base: master
Choose a base branch
from

Conversation

peterbarker
Copy link
Contributor

No description provided.

@peterbarker peterbarker force-pushed the pr/rangefinder-over-327 branch 3 times, most recently from 1bf6995 to 88faf49 Compare August 26, 2024 03:47
@peterbarker peterbarker force-pushed the pr/rangefinder-over-327 branch 2 times, most recently from ea8a289 to 1239beb Compare October 9, 2024 02:10
@peterbarker
Copy link
Contributor Author

Board                    AP_Periph  blimp  bootloader  copter  heli  iofirmware  plane  rover  sub
CubeOrange-periph-heavy  8                                                                     
Durandal                            48     *           200     248               208    264    264
Hitec-Airspeed           *                                                                     
KakuteH7-bdshot                     96     *           328     336               176    264    288
MatekF405                           -8     *           224     200               288    184    200
Pixhawk1-1M-bdshot                  8                  144     312               352    232    224
f103-QiotekPeriph        *                                                                     
f303-Universal           336                                                                   
iomcu                                                                *                         
revo-mini                           32     *           288     280               608    232    304
skyviper-v2450                                         48                                      

@peterbarker peterbarker added DevCallEU and removed WIP labels Oct 9, 2024
@peterbarker peterbarker force-pushed the pr/rangefinder-over-327 branch 11 times, most recently from 5c0e9ae to 09efa59 Compare October 11, 2024 04:38
@peterbarker peterbarker force-pushed the pr/rangefinder-over-327 branch from 09efa59 to 0983029 Compare December 22, 2024 21:33
ArduSub/Log.cpp Outdated
@@ -48,7 +48,7 @@ void Sub::Log_Write_Control_Tuning()
inav_alt : inertial_nav.get_position_z_up_cm() * 0.01f,
baro_alt : barometer.get_altitude(),
desired_rangefinder_alt : (int16_t)mode_surftrak.get_rangefinder_target_cm(),
Copy link
Member

Choose a reason for hiding this comment

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

These now being in different units will be annoying. I would vote to convert this to meters for logging.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

OK, adding a patch.

@@ -67,9 +67,9 @@ bool ModeSurftrak::set_rangefinder_target_cm(float target_cm)
sub.gcs().send_text(MAV_SEVERITY_WARNING, "wrong mode, rangefinder target not set");
} else if (sub.inertial_nav.get_position_z_up_cm() >= sub.g.surftrak_depth) {
sub.gcs().send_text(MAV_SEVERITY_WARNING, "descend below %f meters to set rangefinder target", sub.g.surftrak_depth * 0.01f);
} else if (target_cm < (float)sub.rangefinder_state.min_cm) {
} else if (target_cm < (float)sub.rangefinder_state.min*100) {
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
} else if (target_cm < (float)sub.rangefinder_state.min*100) {
} else if (target_cm < sub.rangefinder_state.min*100) {

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed

sub.gcs().send_text(MAV_SEVERITY_WARNING, "rangefinder target below minimum, ignored");
} else if (target_cm > (float)sub.rangefinder_state.max_cm) {
} else if (target_cm > (float)sub.rangefinder_state.max*100) {
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
} else if (target_cm > (float)sub.rangefinder_state.max*100) {
} else if (target_cm > sub.rangefinder_state.max*100) {

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed.


#if RANGEFINDER_TILT_CORRECTION
// correct alt for angle of the rangefinder
temp_alt = (float)temp_alt * MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z);
temp_alt_m = (float)temp_alt_m * MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z);
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
temp_alt_m = (float)temp_alt_m * MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z);
temp_alt_m = temp_alt_m * MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z);

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed

@@ -3177,6 +3177,26 @@ function rangefinder:max_distance_cm_orient(orientation) end
---@return integer
function rangefinder:distance_cm_orient(orientation) end

-- desc
Copy link
Member

Choose a reason for hiding this comment

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

Full descriptions please.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed. Note that I did just copy the block above which used that "desc" thing :-)

Copy link
Member

Choose a reason for hiding this comment

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

Fixed. Note that I did just copy the block above which used that "desc" thing :-)

Yeah, stuff that pre-dates the docs gets a pass, anything new does not. I need to take another pass at filling in the missing ones.

@@ -252,10 +252,18 @@ singleton RangeFinder rename rangefinder
singleton RangeFinder method num_sensors uint8_t
singleton RangeFinder method has_orientation boolean Rotation'enum ROTATION_NONE ROTATION_MAX-1
singleton RangeFinder method distance_cm_orient uint16_t Rotation'enum ROTATION_NONE ROTATION_MAX-1
singleton RangeFinder method distance_cm_orient deprecate Use distance_orient (in metres)
Copy link
Member

Choose a reason for hiding this comment

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

Nice! There is also some markup we should add to the docs. If you re-generate it might do that for you..... If not Just add

---@deprecated -- Use distance_orient (in metres)

https://luals.github.io/wiki/annotations/#deprecated

Copy link
Member

Choose a reason for hiding this comment

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

Looks like that will update the static checkers, so you will also have disable that check on any files that need it with:

---@diagnostic disable deprecated

Or move them onto the new method of course....

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Nice! There is also some markup we should add to the docs. If you re-generate it might do that for you..... If not Just add

---@deprecated -- Use distance_orient (in metres)

https://luals.github.io/wiki/annotations/#deprecated

Done

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Looks like that will update the static checkers, so you will also have disable that check on any files that need it with:

---@diagnostic disable deprecated

Or move them onto the new method of course....

I have moved them to the new method - which I really should have done already!

@peterbarker peterbarker force-pushed the pr/rangefinder-over-327 branch from 0983029 to 23bf660 Compare December 23, 2024 21:47
Copy link
Contributor Author

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

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

Thanks for the review, @IamPete1 !

@@ -67,9 +67,9 @@ bool ModeSurftrak::set_rangefinder_target_cm(float target_cm)
sub.gcs().send_text(MAV_SEVERITY_WARNING, "wrong mode, rangefinder target not set");
} else if (sub.inertial_nav.get_position_z_up_cm() >= sub.g.surftrak_depth) {
sub.gcs().send_text(MAV_SEVERITY_WARNING, "descend below %f meters to set rangefinder target", sub.g.surftrak_depth * 0.01f);
} else if (target_cm < (float)sub.rangefinder_state.min_cm) {
} else if (target_cm < (float)sub.rangefinder_state.min*100) {
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed

sub.gcs().send_text(MAV_SEVERITY_WARNING, "rangefinder target below minimum, ignored");
} else if (target_cm > (float)sub.rangefinder_state.max_cm) {
} else if (target_cm > (float)sub.rangefinder_state.max*100) {
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed.


#if RANGEFINDER_TILT_CORRECTION
// correct alt for angle of the rangefinder
temp_alt = (float)temp_alt * MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z);
temp_alt_m = (float)temp_alt_m * MAX(0.707f, ahrs.get_rotation_body_to_ned().c.z);
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed

@@ -3177,6 +3177,26 @@ function rangefinder:max_distance_cm_orient(orientation) end
---@return integer
function rangefinder:distance_cm_orient(orientation) end

-- desc
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed. Note that I did just copy the block above which used that "desc" thing :-)

@@ -252,10 +252,18 @@ singleton RangeFinder rename rangefinder
singleton RangeFinder method num_sensors uint8_t
singleton RangeFinder method has_orientation boolean Rotation'enum ROTATION_NONE ROTATION_MAX-1
singleton RangeFinder method distance_cm_orient uint16_t Rotation'enum ROTATION_NONE ROTATION_MAX-1
singleton RangeFinder method distance_cm_orient deprecate Use distance_orient (in metres)
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Nice! There is also some markup we should add to the docs. If you re-generate it might do that for you..... If not Just add

---@deprecated -- Use distance_orient (in metres)

https://luals.github.io/wiki/annotations/#deprecated

Done

@@ -252,10 +252,18 @@ singleton RangeFinder rename rangefinder
singleton RangeFinder method num_sensors uint8_t
singleton RangeFinder method has_orientation boolean Rotation'enum ROTATION_NONE ROTATION_MAX-1
singleton RangeFinder method distance_cm_orient uint16_t Rotation'enum ROTATION_NONE ROTATION_MAX-1
singleton RangeFinder method distance_cm_orient deprecate Use distance_orient (in metres)
Copy link
Contributor Author

Choose a reason for hiding this comment

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

Looks like that will update the static checkers, so you will also have disable that check on any files that need it with:

---@diagnostic disable deprecated

Or move them onto the new method of course....

I have moved them to the new method - which I really should have done already!

@peterbarker peterbarker force-pushed the pr/rangefinder-over-327 branch 2 times, most recently from 8f566a9 to 3a6a09f Compare December 26, 2024 22:57
@peterbarker
Copy link
Contributor Author

Parameter upgrade was tested with this:

./Tools/autotest/test_param_upgrade.py --vehicle=arducopter --param "RNGFND1_MAX_CM=300->RNGFND1_MAX=3.00" --param "RNGFND2_MIN_CM=678->RNGFND2_MIN=6.78" --param "RNGFNDA_MIN_CM=1->RNGFNDA_MIN=0.01" --param "RNGFND5_GNDCLEAR=103->RNGFND5_GNDCLR=1.03"

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
Development

Successfully merging this pull request may close these issues.

4 participants