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
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 1 addition & 2 deletions ArduCopter/mode_flowhold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -517,8 +517,7 @@ void Copter::ModeFlowHold::update_height_estimate(void)
(double)ins_height,
(double)last_ins_height,
dt_ms);
mavlink_msg_named_value_float_send(MAVLINK_COMM_0, AP_HAL::millis(), "HEST", height_estimate);
mavlink_msg_named_value_float_send(MAVLINK_COMM_1, AP_HAL::millis(), "HEST", height_estimate);
gcs().send_named_float("HEST", height_estimate);
delta_velocity_ne.zero();
last_ins_height = ins_height;
}
Expand Down
65 changes: 21 additions & 44 deletions ArduSub/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -364,58 +364,35 @@ void NOINLINE Sub::send_temperature(mavlink_channel_t chan)
celsius.temperature() * 100);
}

bool NOINLINE Sub::send_info(mavlink_channel_t chan)
bool GCS_MAVLINK_Sub::send_info()
{
// Just do this all at once, hopefully the hard-wire telemetry requirement means this is ok
// Name is char[10]
CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT);
mavlink_msg_named_value_float_send(
chan,
AP_HAL::millis(),
"CamTilt",
1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_tilt) / 2.0f + 0.5f));
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("CamTilt",
1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_tilt) / 2.0f + 0.5f));

CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT);
mavlink_msg_named_value_float_send(
chan,
AP_HAL::millis(),
"CamPan",
1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_pan) / 2.0f + 0.5f));
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("CamPan",
1 - (SRV_Channels::get_output_norm(SRV_Channel::k_mount_pan) / 2.0f + 0.5f));

CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT);
mavlink_msg_named_value_float_send(
chan,
AP_HAL::millis(),
"TetherTrn",
quarter_turn_count/4);
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("TetherTrn",
sub.quarter_turn_count/4);

CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT);
mavlink_msg_named_value_float_send(
chan,
AP_HAL::millis(),
"Lights1",
SRV_Channels::get_output_norm(SRV_Channel::k_rcin9) / 2.0f + 0.5f);
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("Lights1",
SRV_Channels::get_output_norm(SRV_Channel::k_rcin9) / 2.0f + 0.5f);

CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT);
mavlink_msg_named_value_float_send(
chan,
AP_HAL::millis(),
"Lights2",
SRV_Channels::get_output_norm(SRV_Channel::k_rcin10) / 2.0f + 0.5f);
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("Lights2",
SRV_Channels::get_output_norm(SRV_Channel::k_rcin10) / 2.0f + 0.5f);

CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT);
mavlink_msg_named_value_float_send(
chan,
AP_HAL::millis(),
"PilotGain",
gain);
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("PilotGain", sub.gain);

CHECK_PAYLOAD_SIZE2(NAMED_VALUE_FLOAT);
mavlink_msg_named_value_float_send(
chan,
AP_HAL::millis(),
"InputHold",
input_hold_engaged);
CHECK_PAYLOAD_SIZE(NAMED_VALUE_FLOAT);
send_named_float("InputHold", sub.input_hold_engaged);

return true;
}
Expand Down Expand Up @@ -503,7 +480,7 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
switch (id) {

case MSG_NAMED_FLOAT:
sub.send_info(chan);
send_info();
break;

case MSG_EXTENDED_STATUS1:
Expand Down
2 changes: 2 additions & 0 deletions ArduSub/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,8 @@ class GCS_MAVLINK_Sub : public GCS_MAVLINK {
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
bool try_send_message(enum ap_message id) override;

bool send_info(void);

MAV_TYPE frame_type() const override;
MAV_MODE base_mode() const override;
uint32_t custom_mode() const override;
Expand Down
1 change: 0 additions & 1 deletion ArduSub/Sub.h
Original file line number Diff line number Diff line change
Expand Up @@ -487,7 +487,6 @@ class Sub : public AP_HAL::HAL::Callbacks {
void rpm_update();
#endif
void send_temperature(mavlink_channel_t chan);
bool send_info(mavlink_channel_t chan);
void send_pid_tuning(mavlink_channel_t chan);
void gcs_data_stream_send(void);
void gcs_check_input(void);
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Airspeed/AP_Airspeed.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -401,7 +401,7 @@ void AP_Airspeed::read(void)
#if 1
// debugging until we get MAVLink support for 2nd airspeed sensor
if (enabled(1)) {
mavlink_msg_named_value_float_send(MAVLINK_COMM_0, AP_HAL::millis(), "AS2", get_airspeed(1));
gcs().send_named_float("AS2", get_airspeed(1));
}
#endif

Expand Down
5 changes: 5 additions & 0 deletions libraries/GCS_MAVLink/GCS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,11 @@ void GCS::send_text(MAV_SEVERITY severity, const char *fmt, ...)
} \
} while (0)

void GCS::send_named_float(const char *name, float value) const
{
FOR_EACH_ACTIVE_CHANNEL(send_named_float(name, value));
}

void GCS::send_home(const Location &home) const
{
FOR_EACH_ACTIVE_CHANNEL(send_home(home));
Expand Down
2 changes: 2 additions & 0 deletions libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -184,6 +184,7 @@ class GCS_MAVLINK
void send_autopilot_version() const;
void send_local_position() const;
void send_vibration() const;
void send_named_float(const char *name, float value) const;
void send_home(const Location &home) const;
void send_ekf_origin(const Location &ekf_origin) const;
void send_servo_output_raw(bool hil);
Expand Down Expand Up @@ -537,6 +538,7 @@ class GCS
virtual uint8_t num_gcs() const = 0;
void send_message(enum ap_message id);
void send_mission_item_reached_message(uint16_t mission_index);
void send_named_float(const char *name, float value) const;
void send_home(const Location &home) const;
void send_ekf_origin(const Location &ekf_origin) const;

Expand Down
10 changes: 9 additions & 1 deletion libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -585,11 +585,12 @@ void GCS_MAVLINK::handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg)

void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...)
{
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] {};
char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
va_list arg_list;
va_start(arg_list, fmt);
hal.util->vsnprintf((char *)text, sizeof(text), fmt, arg_list);
va_end(arg_list);
text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = 0;
gcs().send_statustext(severity, (1<<chan), text);
}

Expand Down Expand Up @@ -1525,6 +1526,13 @@ 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.

strncpy(float_name, name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
mavlink_msg_named_value_float_send(chan, AP_HAL::millis(), float_name, value);
}

void GCS_MAVLINK::send_home(const Location &home) const
{
if (HAVE_PAYLOAD_SPACE(chan, HOME_POSITION)) {
Expand Down