Skip to content

Commit

Permalink
changes for increasing frequency
Browse files Browse the repository at this point in the history
  • Loading branch information
Astik-2002 committed Feb 18, 2024
1 parent b7a3ece commit d29cf1a
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 52 deletions.
5 changes: 1 addition & 4 deletions libraries/AP_DDS/AP_DDS_Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
static constexpr uint8_t ENABLED_BY_DEFAULT = 1;
static constexpr uint16_t DELAY_TIME_TOPIC_MS = 10;
static constexpr uint16_t DELAY_BATTERY_STATE_TOPIC_MS = 1000;
static constexpr uint16_t DELAY_IMU_TOPIC_MS = 100;
static constexpr uint16_t DELAY_IMU_TOPIC_MS = 5;
static constexpr uint16_t DELAY_LOCAL_POSE_TOPIC_MS = 33;
static constexpr uint16_t DELAY_LOCAL_VELOCITY_TOPIC_MS = 33;
static constexpr uint16_t DELAY_GEO_POSE_TOPIC_MS = 33;
Expand Down Expand Up @@ -1004,10 +1004,7 @@ void AP_DDS_Client::write_imu_topic()
if (!success) {
// TODO sometimes serialization fails on bootup. Determine why.
// AP_HAL::panic("FATAL: DDS_Client failed to serialize\n");
gcs().send_text(MAV_SEVERITY_INFO,"imu data not serialized");
}
else
gcs().send_text(MAV_SEVERITY_INFO,"imu data serialized");
}
}

Expand Down
48 changes: 0 additions & 48 deletions libraries/AP_DDS/Idl/sensor_msgs/msg/IMU.idl

This file was deleted.

0 comments on commit d29cf1a

Please sign in to comment.