From d29cf1aa01c88b5058fa9bddcf1c131d0059315e Mon Sep 17 00:00:00 2001 From: astik <41.astiksrivastava@gmail.com> Date: Sun, 18 Feb 2024 09:27:45 +0530 Subject: [PATCH] changes for increasing frequency --- libraries/AP_DDS/AP_DDS_Client.cpp | 5 +- libraries/AP_DDS/Idl/sensor_msgs/msg/IMU.idl | 48 -------------------- 2 files changed, 1 insertion(+), 52 deletions(-) delete mode 100644 libraries/AP_DDS/Idl/sensor_msgs/msg/IMU.idl diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index 3d1dd04379f22f..c44cf561c3dcd2 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -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; @@ -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"); } } diff --git a/libraries/AP_DDS/Idl/sensor_msgs/msg/IMU.idl b/libraries/AP_DDS/Idl/sensor_msgs/msg/IMU.idl deleted file mode 100644 index 2770316110bf82..00000000000000 --- a/libraries/AP_DDS/Idl/sensor_msgs/msg/IMU.idl +++ /dev/null @@ -1,48 +0,0 @@ -// generated from rosidl_adapter/resource/msg.idl.em -// with input from sensor_msgs/msg/Imu.msg -// generated code does not contain a copyright notice - -#include "geometry_msgs/msg/Quaternion.idl" -#include "geometry_msgs/msg/Vector3.idl" -#include "std_msgs/msg/Header.idl" - -module sensor_msgs { - module msg { - typedef double double__9[9]; - @verbatim (language="comment", text= - "This is a message to hold data from an IMU (Inertial Measurement Unit)" "\n" - "" "\n" - "Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec" "\n" - "" "\n" - "If the covariance of the measurement is known, it should be filled in (if all you know is the" "\n" - "variance of each measurement, e.g. from the datasheet, just put those along the diagonal)" "\n" - "A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the" "\n" - "data a covariance will have to be assumed or gotten from some other source" "\n" - "" "\n" - "If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an" "\n" - "orientation estimate), please set element 0 of the associated covariance matrix to -1" "\n" - "If you are interpreting this message, please check for a value of -1 in the first element of each" "\n" - "covariance matrix, and disregard the associated estimate.") - struct Imu { - std_msgs::msg::Header header; - - geometry_msgs::msg::Quaternion orientation; - - @verbatim (language="comment", text= - "Row major about x, y, z axes") - double__9 orientation_covariance; - - geometry_msgs::msg::Vector3 angular_velocity; - - @verbatim (language="comment", text= - "Row major about x, y, z axes") - double__9 angular_velocity_covariance; - - geometry_msgs::msg::Vector3 linear_acceleration; - - @verbatim (language="comment", text= - "Row major x, y z") - double__9 linear_acceleration_covariance; - }; - }; -};