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

GCS_MAVLink: added ALTITUDE message #141 #21652

Closed

Conversation

peterbarker
Copy link
Contributor

No description provided.

if (rangefinder != nullptr) {
const AP_RangeFinder_Backend *s = rangefinder->find_instance(ROTATION_PITCH_270);
if (s != nullptr) {
bottom_clearance = s->distance_cm()*0.01;
Copy link
Contributor

Choose a reason for hiding this comment

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

If this is out of range somewhere shouldn't we fall back to terrain if we have it, and failing that fall back to relative? I don't see any masking/flags to let a GCS otherwise differentiate on these values.

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 think so. I'm actually confused as how this would be different to terrain - except that perhaps terrain wouldn't fall back to relative?

Copy link
Contributor

Choose a reason for hiding this comment

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

Technically terrain should be ground level, while clearance would include things like top of tree, building, whatever rose off the ground below you.

@peterbarker
Copy link
Contributor Author

I brought this up for discussion at the DevCall. I've also fixed the compilation so we can see what it costs.

A few things came up. The first is that @hendjoshsr71 pointed out this isn't really a good "all in one altitude message". It doesn't include any information about qnh altitudes, perhaps the most important thing up-and-coming.

tridge suggested we could add a "is_for_current_location" boolean to the TERRAIN_REPORT message - Randy amended that to "a flags field", but the intent is the same. Reuse the existing TERRAIN_REPORT message but include additional information sufficient for the GCS to know this is the current altitude above terrain. I did note we'd need to take the whole extension-field-zero semantics into account when creating the flags field.

No determination was come to - I ran out of time to progress this on the call, but at least we have more talking points.

@peterbarker
Copy link
Contributor Author

Durandal:

 Binary Name      Text [B]        Data [B]     BSS (B)        Total Flash Change [B] (%)      Flash Free After PR (B)
---------------  --------------  -----------  -------------  ----------------------------  -------------------------
blimp            504 (+0.0389%)  0 (0.0000%)  0 (0.0000%)    504 (+0.0388%)                                   668232
ardusub          524 (+0.0335%)  0 (0.0000%)  4 (+0.0015%)   524 (+0.0334%)                                   398952
ardurover        520 (+0.0323%)  0 (0.0000%)  0 (0.0000%)    520 (+0.0322%)                                   351116
antennatracker   524 (+0.0387%)  0 (0.0000%)  -4 (-0.0015%)  524 (+0.0387%)                                   610324
arduplane        524 (+0.0298%)  0 (0.0000%)  -4 (-0.0015%)  524 (+0.0297%)                                   201396
arducopter-heli  524 (+0.0293%)  0 (0.0000%)  4 (+0.0015%)   524 (+0.0293%)                                   175732
arducopter       524 (+0.0294%)  0 (0.0000%)  4 (+0.0015%)   524 (+0.0294%)                                   182764

if (!_ahrs.get_location(loc)) {
return;
}
const float altitude_amsl = global_position_int_alt() * 0.001; //meters above ground/sea level
Copy link
Contributor

Choose a reason for hiding this comment

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

Is 0.001 correct here?

#endif

float bottom_clearance = -1; //mavlink specs value for unavailable
const RangeFinder *rangefinder = RangeFinder::get_singleton();
Copy link
Contributor

Choose a reason for hiding this comment

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

Why not use AP?

float bottom_clearance = -1; //mavlink specs value for unavailable
const RangeFinder *rangefinder = RangeFinder::get_singleton();
if (rangefinder != nullptr) {
const AP_RangeFinder_Backend *s = rangefinder->find_instance(ROTATION_PITCH_270);
Copy link
Contributor

Choose a reason for hiding this comment

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

This would likely benefit from an earth frame rotation.

@peterbarker peterbarker force-pushed the pr/add-altitude-message branch 2 times, most recently from 17d4d78 to b4af3cd Compare June 17, 2023 01:24
@peterbarker peterbarker force-pushed the pr/add-altitude-message branch from b4af3cd to c332c64 Compare December 13, 2023 03:35
@peterbarker peterbarker deleted the pr/add-altitude-message branch September 17, 2024 01:23
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants