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

Stop sending sensor offsets mavlink message #18368

Merged
merged 7 commits into from
Aug 18, 2021
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
1 change: 0 additions & 1 deletion AntennaTracker/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -264,7 +264,6 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = {
MSG_SCALED_PRESSURE,
MSG_SCALED_PRESSURE2,
MSG_SCALED_PRESSURE3,
MSG_SENSOR_OFFSETS
};
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
MSG_SYS_STATUS,
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -437,7 +437,6 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = {
MSG_SCALED_PRESSURE,
MSG_SCALED_PRESSURE2,
MSG_SCALED_PRESSURE3,
MSG_SENSOR_OFFSETS
};
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
MSG_SYS_STATUS,
Expand Down
1 change: 0 additions & 1 deletion ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -486,7 +486,6 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = {
MSG_SCALED_PRESSURE,
MSG_SCALED_PRESSURE2,
MSG_SCALED_PRESSURE3,
MSG_SENSOR_OFFSETS
};
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
MSG_SYS_STATUS,
Expand Down
3 changes: 1 addition & 2 deletions ArduSub/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -322,7 +322,6 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = {
MSG_SCALED_PRESSURE,
MSG_SCALED_PRESSURE2,
MSG_SCALED_PRESSURE3,
MSG_SENSOR_OFFSETS
};
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
MSG_SYS_STATUS,
Expand Down Expand Up @@ -832,4 +831,4 @@ uint8_t GCS_MAVLINK_Sub::high_latency_tgt_airspeed() const
}
return 0;
}
#endif // HAL_HIGH_LATENCY2_ENABLED
#endif // HAL_HIGH_LATENCY2_ENABLED
3 changes: 1 addition & 2 deletions Blimp/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -299,7 +299,6 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = {
MSG_SCALED_PRESSURE,
MSG_SCALED_PRESSURE2,
MSG_SCALED_PRESSURE3,
MSG_SENSOR_OFFSETS
};
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
MSG_SYS_STATUS,
Expand Down Expand Up @@ -664,4 +663,4 @@ uint8_t GCS_MAVLINK_Blimp::high_latency_wind_direction() const
// need to convert -180->180 to 0->360/2
return wrap_360(degrees(atan2f(-wind.y, -wind.x))) / 2;
}
#endif // HAL_HIGH_LATENCY2_ENABLED
#endif // HAL_HIGH_LATENCY2_ENABLED
3 changes: 1 addition & 2 deletions Rover/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -466,7 +466,6 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = {
MSG_SCALED_PRESSURE,
MSG_SCALED_PRESSURE2,
MSG_SCALED_PRESSURE3,
MSG_SENSOR_OFFSETS
};
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
MSG_SYS_STATUS,
Expand Down Expand Up @@ -1111,4 +1110,4 @@ uint8_t GCS_MAVLINK_Rover::high_latency_wind_direction() const
}
return 0;
}
#endif // HAL_HIGH_LATENCY2_ENABLED
#endif // HAL_HIGH_LATENCY2_ENABLED
7 changes: 0 additions & 7 deletions libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -244,7 +244,6 @@ class GCS_MAVLINK
void send_scaled_pressure();
void send_scaled_pressure2();
virtual void send_scaled_pressure3(); // allow sub to override this
void send_sensor_offsets();
void send_simstate() const;
void send_sim_state() const;
void send_ahrs();
Expand Down Expand Up @@ -867,12 +866,6 @@ class GCS_MAVLINK

uint8_t last_battery_status_idx;

// send_sensor_offsets decimates its send rate using this counter:
// FIXME: decimate this instead when initialising the message
// intervals from the stream rates. Consider the implications of
// doing so vis-a-vis the fact it will consume a bucket.
uint8_t send_sensor_offsets_counter;

// if we've ever sent a DISTANCE_SENSOR message out of an
// orientation we continue to send it out, even if it is not
// longer valid.
Expand Down
39 changes: 0 additions & 39 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -807,7 +807,6 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
{ MAVLINK_MSG_ID_SCALED_PRESSURE, MSG_SCALED_PRESSURE},
{ MAVLINK_MSG_ID_SCALED_PRESSURE2, MSG_SCALED_PRESSURE2},
{ MAVLINK_MSG_ID_SCALED_PRESSURE3, MSG_SCALED_PRESSURE3},
{ MAVLINK_MSG_ID_SENSOR_OFFSETS, MSG_SENSOR_OFFSETS},
{ MAVLINK_MSG_ID_GPS_RAW_INT, MSG_GPS_RAW},
{ MAVLINK_MSG_ID_GPS_RTK, MSG_GPS_RTK},
{ MAVLINK_MSG_ID_GPS2_RAW, MSG_GPS2_RAW},
Expand Down Expand Up @@ -1822,39 +1821,6 @@ void GCS_MAVLINK::send_scaled_pressure3()
send_scaled_pressure_instance(2, mavlink_msg_scaled_pressure3_send);
}

void GCS_MAVLINK::send_sensor_offsets()
{
const AP_InertialSensor &ins = AP::ins();
const Compass &compass = AP::compass();

// run this message at a much lower rate - otherwise it
// pointlessly wastes quite a lot of bandwidth
if (send_sensor_offsets_counter++ < 10) {
Copy link
Contributor

Choose a reason for hiding this comment

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

Ha! This defeats a lot of the scheduling/buffering code as well because it's harder to land on the right order with stuff like this confusing the buffer backoffs :P

return;
}
send_sensor_offsets_counter = 0;

const Vector3f &mag_offsets = compass.get_offsets(0);
const Vector3f &accel_offsets = ins.get_accel_offsets(0);
const Vector3f &gyro_offsets = ins.get_gyro_offsets(0);

const AP_Baro &barometer = AP::baro();

mavlink_msg_sensor_offsets_send(chan,
mag_offsets.x,
mag_offsets.y,
mag_offsets.z,
compass.get_declination(),
barometer.get_pressure(),
barometer.get_temperature()*100,
Copy link
Contributor

Choose a reason for hiding this comment

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

This isn't actually available via the parameters, but it is in the scaled pressure, which is better anyways.

gyro_offsets.x,
gyro_offsets.y,
gyro_offsets.z,
accel_offsets.x,
accel_offsets.y,
accel_offsets.z);
}

void GCS_MAVLINK::send_ahrs()
{
const AP_AHRS &ahrs = AP::ahrs();
Expand Down Expand Up @@ -5018,11 +4984,6 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
send_scaled_pressure3();
break;

case MSG_SENSOR_OFFSETS:
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
send_sensor_offsets();
break;

case MSG_SERVO_OUTPUT_RAW:
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
send_servo_output_raw();
Expand Down
1 change: 0 additions & 1 deletion libraries/GCS_MAVLink/ap_message.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@ enum ap_message : uint8_t {
MSG_SCALED_PRESSURE,
MSG_SCALED_PRESSURE2,
MSG_SCALED_PRESSURE3,
MSG_SENSOR_OFFSETS,
MSG_GPS_RAW,
MSG_GPS_RTK,
MSG_GPS2_RAW,
Expand Down