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: Benewake-TFminiP driver outputs init failure to ground station #13300

Closed
wants to merge 2 commits into from

Conversation

ashvath100
Copy link
Contributor

Fixes #12396
checks the version of the lidar and if it's too low, outputs a text string to the user.

@ashvath100 ashvath100 changed the title AP_RangeFinder: Benewake-TFminiP driver output init failure to ground station AP_RangeFinder: Benewake-TFminiP driver outputs init failure to ground station Jan 16, 2020
Copy link
Contributor

@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.

This is a good find - thanks!

@rmackay9
Copy link
Contributor

I wonder if the message will be visible on the ground station because the init will happen very early on in the startup. I suspect it will appear but it would be good to confirm.

@@ -102,6 +104,8 @@ bool AP_RangeFinder_Benewake_TFMiniPlus::init()
if (val[5] * 10000 + val[4] * 100 + val[3] < 20003) {
hal.console->printf(DRIVER ": minimum required FW version 2.0.3, but version %u.%u.%u found\n",
val[5], val[4], val[3]);
gcs().send_text(MAV_SEVERITY_CRITICAL, ": minimum required FW version 2.0.3, but version %u.%u.%u found",
Copy link
Contributor

Choose a reason for hiding this comment

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

It's funny that there is nothing before the ":". In the printf it has DRIVER. I also think this line is too long for a send-text which has a max length of 50 characters. Maybe try making it short like, "BenewakeTFMini: FW ver %u.%u.%u (2.0.3 required)"

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Does "TFMini: FW ver %u.%u.%u (need>=2.0.3)" sound fine ?

Copy link
Contributor

Choose a reason for hiding this comment

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

Yes, that's fine I think.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

The correction has been done

@peterbarker
Copy link
Contributor

peterbarker commented Jan 17, 2020 via email

@@ -102,6 +104,8 @@ bool AP_RangeFinder_Benewake_TFMiniPlus::init()
if (val[5] * 10000 + val[4] * 100 + val[3] < 20003) {
hal.console->printf(DRIVER ": minimum required FW version 2.0.3, but version %u.%u.%u found\n",
val[5], val[4], val[3]);
gcs().send_text(MAV_SEVERITY_CRITICAL, "TFMini: FW ver %u.%u.%u (need>=2.0.3)",
Copy link
Contributor

Choose a reason for hiding this comment

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

This is being called with a semaphore held. This is actually really not a good idea - we want to cross as little code as possible when holding a semaphore - and gcs().send_text() isn't it :-)

Could you stash the three values in some variables and detect the version problem outside the semaphore-held part, please?

@@ -102,6 +104,8 @@ bool AP_RangeFinder_Benewake_TFMiniPlus::init()
if (val[5] * 10000 + val[4] * 100 + val[3] < 20003) {
hal.console->printf(DRIVER ": minimum required FW version 2.0.3, but version %u.%u.%u found\n",
Copy link
Contributor

Choose a reason for hiding this comment

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

We can do without this once we have the send_text.

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 still need to check the version here right ? since it decides if we goto fail or not

@@ -102,6 +104,8 @@ bool AP_RangeFinder_Benewake_TFMiniPlus::init()
if (val[5] * 10000 + val[4] * 100 + val[3] < 20003) {
hal.console->printf(DRIVER ": minimum required FW version 2.0.3, but version %u.%u.%u found\n",
val[5], val[4], val[3]);
gcs().send_text(MAV_SEVERITY_CRITICAL, "TFMini: FW ver %u.%u.%u (need>=2.0.3)",
Copy link
Contributor

Choose a reason for hiding this comment

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

Oh, also, "CRITICAL" might going a bit far :-)

How about MAV_SEVERITY_ERROR?

Copy link
Contributor

Choose a reason for hiding this comment

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

I was the one who actually suggested MAV_SEVERITY_CRITICAL so let's not give @ashvath100 too much run around.

if (ver[0] * 10000 + ver[1] * 100 + ver[3] < 20003) {
gcs().send_text(MAV_SEVERITY_ERROR, "TFMini: FW ver %u.%u.%u (need>=2.0.3)",
(unsigned)ver[0],(unsigned)ver[1],(unsigned)ver[2]);
}
Copy link
Contributor

Choose a reason for hiding this comment

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

this code will never execute since you have the return false just above this

Copy link
Contributor

Choose a reason for hiding this comment

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

and you are checking the version again. I disagree with @peterbarker here: the failure is just on init and the additional time we hold the semaphore for this error condition doesn't matter much. I'd say to either move it where it was or change it in such a way you don't check the version twice.

@rmackay9
Copy link
Contributor

I guess you're going to open another PR @ashvath100? Sorry for the difficulties in getting this into master but you're almost there. Tell me if you'd prefer I just take your changes and modify them enough to get them merged.

@ashvath100
Copy link
Contributor Author

ashvath100 commented Jan 21, 2020

I guess you're going to open another PR @ashvath100? Sorry for the difficulties in getting this into master but you're almost there. Tell me if you'd prefer I just take your changes and modify them enough to get them merged.

@rmackay9 I'll be happy to finish the work , could you please clarify me on the semaphore issue whether or not the send_text() should be moved else where , if yes how do you propose we move it considering we will have to check the version again if we don't want to call any functions through the existing check

@peterbarker had suggested to use severity ERROR while you suggest to use CRITICAL , which should we finally use

@ashvath100 ashvath100 reopened this Jan 21, 2020
@rmackay9
Copy link
Contributor

@ashvath100,

MAV_SEVERITY_ERROR is probably best. Sorry for the confusion. The important thing for me is that it appears on the Mission Planner HUD in red letters... it should if sent as MAV_SEVERITY_ERROR (or _CRITICAL).

I'm not sure where the send-text should be placed in the code.

@tatsuy
Copy link
Contributor

tatsuy commented Dec 21, 2020

this was merged by #16102.
Please close this if that's OK with you.

@peterbarker
Copy link
Contributor

@ashvath100 - you reopened?

@ashvath100 ashvath100 closed this Dec 21, 2020
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.

AP_RangeFinder: Benewake-TFminiPlus driver should output init failure to ground station
5 participants