From 9030c5b0de7a79c1ffbec85566cdd946db9ae9b1 Mon Sep 17 00:00:00 2001 From: Mykhailo Kuznietsov Date: Wed, 11 Oct 2023 18:41:52 +1100 Subject: [PATCH] AP_DDS: Fix some typos Fixed some typos found in the code. --- libraries/AP_DDS/AP_DDS_Client.cpp | 4 ++-- libraries/AP_DDS/AP_DDS_External_Odom.cpp | 4 ++-- libraries/AP_DDS/README.md | 6 +++--- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index d5315e8297..4f962574f7 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -300,7 +300,7 @@ void AP_DDS_Client::update_topic(geometry_msgs_msg_PoseStamped& msg) // Z - Up // https://www.ros.org/reps/rep-0103.html#axis-orientation // As a consequence, to follow ROS REP 103, it is necessary to switch X and Y, - // as well as invert Z (NED to ENU convertion) as well as a 90 degree rotation in the Z axis + // as well as invert Z (NED to ENU conversion) as well as a 90 degree rotation in the Z axis // for x to point forward Quaternion orientation; if (ahrs.get_quaternion(orientation)) { @@ -377,7 +377,7 @@ void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPoseStamped& msg) // Z - Up // https://www.ros.org/reps/rep-0103.html#axis-orientation // As a consequence, to follow ROS REP 103, it is necessary to switch X and Y, - // as well as invert Z (NED to ENU convertion) as well as a 90 degree rotation in the Z axis + // as well as invert Z (NED to ENU conversion) as well as a 90 degree rotation in the Z axis // for x to point forward Quaternion orientation; if (ahrs.get_quaternion(orientation)) { diff --git a/libraries/AP_DDS/AP_DDS_External_Odom.cpp b/libraries/AP_DDS/AP_DDS_External_Odom.cpp index cf121f4085..8d8563e5e8 100644 --- a/libraries/AP_DDS/AP_DDS_External_Odom.cpp +++ b/libraries/AP_DDS/AP_DDS_External_Odom.cpp @@ -27,7 +27,7 @@ void AP_DDS_External_Odom::handle_external_odom(const tf2_msgs_msg_TFMessage& ms convert_transform(ros_transform_stamped.transform, ap_position, ap_rotation); // Although ROS convention states quaternions in ROS messages should be normalized, it's not guaranteed. - // Before propogating a potentially inaccurate quaternion to the rest of AP, normalize it here. + // Before propagating a potentially inaccurate quaternion to the rest of AP, normalize it here. // TODO what if the quaternion is NaN? ap_rotation.normalize(); @@ -38,7 +38,7 @@ void AP_DDS_External_Odom::handle_external_odom(const tf2_msgs_msg_TFMessage& ms // https://www.ros.org/reps/rep-0105.html#id16 // Thus, there will not be any resets. const uint8_t reset_counter {0}; - // TODO imlement jitter correction similar to GCS_MAVLINK::correct_offboard_timestamp_usec_to_ms(remote_time_us, sizeof(msg)); + // TODO implement jitter correction similar to GCS_MAVLINK::correct_offboard_timestamp_usec_to_ms(remote_time_us, sizeof(msg)); const uint32_t time_ms {static_cast(remote_time_us * 1E-3)}; visual_odom->handle_pose_estimate(remote_time_us, time_ms, ap_position.x, ap_position.y, ap_position.z, ap_rotation, posErr, angErr, reset_counter); diff --git a/libraries/AP_DDS/README.md b/libraries/AP_DDS/README.md index d4a0e15bb2..3e89398599 100644 --- a/libraries/AP_DDS/README.md +++ b/libraries/AP_DDS/README.md @@ -84,7 +84,7 @@ While DDS support in Ardupilot is mostly through git submodules, another tool ne ``` > :warning: **If you have installed FastDDS or FastDDSGen globally on your system**: -eProsima's libraries and the packaging system in Ardupilot are not determistic in this scenario. +eProsima's libraries and the packaging system in Ardupilot are not deterministic in this scenario. You may experience the wrong version of a library brought in, or runtime segfaults. For now, avoid having simultaneous local and global installs. If you followed the [global install](https://fast-dds.docs.eprosima.com/en/latest/installation/sources/sources_linux.html#global-installation) @@ -139,7 +139,7 @@ Follow the steps to use the microROS Agent sudo apt install ros-humble-geographic-msgs ``` -- Install and run the microROS agent (as descibed here). Make sure to use the `humble` branch. +- Install and run the microROS agent (as described here). Make sure to use the `humble` branch. - Follow [the instructions](https://micro.ros.org/docs/tutorials/core/first_application_linux/) for the following: - Do "Installing ROS 2 and the micro-ROS build system" @@ -321,7 +321,7 @@ provided a few rules are followed when defining the entries in #### ROS 2 message and service interface types -ROS 2 message and interface defintions are mangled by the `rosidl_adapter` when +ROS 2 message and interface definitions are mangled by the `rosidl_adapter` when mapping from ROS 2 to DDS to avoid naming conflicts in the C/C++ libraries. The ROS 2 object `namespace::Struct` is mangled to `namespace::dds_::Struct_` for DDS. The table below provides some example mappings: