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

Use named float wrapper to fix GCC 8.1 compile error #8383

Merged
merged 4 commits into from
May 16, 2018

Conversation

WickedShell
Copy link
Contributor

Fixes #8353 with a silly 10 byte name. Required to let GCC 8.1 work.

@magicrub
Copy link
Contributor

Question, does C do the usual thing of appending a null char to that string? If so, does that make it 11 chars?

I imagine if you took a couple off then gcc gets mad, but does it also get mad if you have too many?

@patrickelectric
Copy link
Member

It was not possible to compile with this patch, did you tried it ?

@WickedShell
Copy link
Contributor Author

WickedShell commented May 13, 2018

@patrickelectric it compiles for me with GCC 8.1, what compiler are you using, and whats the error? (Also compiles under all of CI correctly)

@WickedShell
Copy link
Contributor Author

@magicrub your right, it was appending a character, I've removed an unneeded one, and it doesn't care if there are to many. The complaint was memcpy'ing out of bounds from the string, if the string is larger then we copy it doesn't care.

@patrickelectric
Copy link
Member

This same function is used in other places around the code.

ArduCopter/mode_flowhold.cpp:    mavlink_msg_named_value_float_send(MAVLINK_COMM_0, AP_HAL::millis(), "HEST", height_estimate);
ArduCopter/mode_flowhold.cpp:    mavlink_msg_named_value_float_send(MAVLINK_COMM_1, AP_HAL::millis(), "HEST", height_estimate);
ArduSub/GCS_Mavlink.cpp:    mavlink_msg_named_value_float_send(
ArduSub/GCS_Mavlink.cpp:    mavlink_msg_named_value_float_send(
ArduSub/GCS_Mavlink.cpp:    mavlink_msg_named_value_float_send(
ArduSub/GCS_Mavlink.cpp:    mavlink_msg_named_value_float_send(
ArduSub/GCS_Mavlink.cpp:    mavlink_msg_named_value_float_send(
ArduSub/GCS_Mavlink.cpp:    mavlink_msg_named_value_float_send(
ArduSub/GCS_Mavlink.cpp:    mavlink_msg_named_value_float_send(

Compiler:

gcc (GCC) 8.1.0
Copyright (C) 2018 Free Software Foundation, Inc.
This is free software; see the source for copying conditions.  There is NO
warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.

Output: https://paste.kde.org/pzlcyl37c

@WickedShell
Copy link
Contributor Author

@patrickelectric Oh, that's the same class of issue, just affecting the other vehicles. (I was testing Plane here at the time), those vehicles would also need similar changes to resolve them.

@tridge
Copy link
Contributor

tridge commented May 15, 2018

I think a wrapper function in the GCS_MAVLink library would be a better soln for this

@WickedShell
Copy link
Contributor Author

Added a wrapper, if everyone (@peterbarker @OXINARF @tridge ) is good with this approach I will fix the sub/copter versions of this tomorrow and push them to this PR.

@peterbarker
Copy link
Contributor

LGTM.

Noting, however, that it's a significant behavioural change, sending to all active channels rather than just a special, magic one.

@WickedShell
Copy link
Contributor Author

WickedShell commented May 15, 2018 via email

@WickedShell
Copy link
Contributor Author

WickedShell commented May 15, 2018 via email

Copy link
Member

@OXINARF OXINARF left a comment

Choose a reason for hiding this comment

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

@WickedShell I was expecting changes to all the other places where this is used too. That was the purpose of adding a wrapper 😉

@@ -1525,6 +1526,14 @@ void GCS_MAVLINK::send_vibration() const
ins.get_accel_clip_count(2));
}

void GCS_MAVLINK::send_named_float(const char *name, float value) const
{
char float_name[MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN+1] {};
Copy link
Member

Choose a reason for hiding this comment

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

Why the +1? The char array needs exactly MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN. Contrary to vsnprintf, strncpy will copy every character until it can, it doesn't reserve space for null-terminator.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Because if you don't do that, with GCC 8.1 you have to deal with the following warning:

../../libraries/GCS_MAVLink/GCS_Common.cpp: In member function ‘void GCS_MAVLINK::send_named_float(const char*, float) const’:
../../libraries/GCS_MAVLink/GCS_Common.cpp:1532:12: warning: ‘char* strncpy(char*, const char*, size_t)’ specified bound 10 equals destination size [-Wstringop-truncation]
     strncpy(float_name, name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
     ~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

I'm flooded with these for statustexts, and was just trying to not add an additional one. (But I agree it's not actually needed for MAVLink). If we want to turn off the warning then I can see removing it...

Copy link
Member

@OXINARF OXINARF May 16, 2018

Choose a reason for hiding this comment

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

GCC 8.1 is killing me. Is it a compiler or a teaching tool? Gosh.

Anyway, rather than disabling the warning I'd prefer to use the strategy that GCC docs suggest (https://gcc.gnu.org/onlinedocs/gcc/Warning-Options.html): To avoid the warning when the result is not expected to be NUL-terminated, call memcpy instead.

The incoming string has to be NUL-terminated, so doing a memcpy should always work, it either sends a NUL-terminated string smaller than the array size or it sends a not NUL-terminated string truncated to the array size.

{
char float_name[MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN+1] {};
strncpy(float_name, name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
float_name[MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN] = 0;
Copy link
Member

Choose a reason for hiding this comment

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

Again, why? This array position won't be read/copied by the MAVLink code.

@WickedShell WickedShell requested a review from jaxxzer May 16, 2018 06:50
@WickedShell WickedShell changed the title AP_Airspeed: Send named float from a 10 byte source Use named float wrapper to fix GCC 8.1 compile error May 16, 2018
@WickedShell
Copy link
Contributor Author

Copter and Sub are both wrapped now, copter now sends to all active channels as well. I ran the behavior changes past tridge and randy on mumble and got affirmative opinions on the behavior change of sending to all channels as being correct.

@WickedShell WickedShell force-pushed the wickedshell/airspeed-param branch 3 times, most recently from e0928ac to 8233cb3 Compare May 16, 2018 22:52
@OXINARF OXINARF merged commit 2d7f60a into ArduPilot:master May 16, 2018
@OXINARF
Copy link
Member

OXINARF commented May 16, 2018

Merged, thanks!

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

Successfully merging this pull request may close these issues.

None yet

7 participants