Skip to content

Commit

Permalink
feat: change autoware_universe_utils package dependence to autoware_u…
Browse files Browse the repository at this point in the history
…tils

Signed-off-by: Motsu-san <[email protected]>
  • Loading branch information
Motsu-san committed Feb 4, 2025
1 parent 11df704 commit 75b4201
Show file tree
Hide file tree
Showing 6 changed files with 28 additions and 28 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,9 @@
#include "autoware/ekf_localizer/hyper_parameters.hpp"
#include "autoware/ekf_localizer/warning.hpp"

#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware/universe_utils/ros/logger_level_configure.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
#include <autoware_utils/geometry/geometry.hpp>
#include <autoware_utils/ros/logger_level_configure.hpp>
#include <autoware_utils/system/stop_watch.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float64_multi_array_stamped.hpp>
Expand Down Expand Up @@ -110,7 +110,7 @@ class EKFLocalizer : public rclcpp::Node
tf2_ros::TransformListener tf2_listener_;

//!< @brief logger configure module
std::unique_ptr<autoware::universe_utils::LoggerLevelConfigure> logger_configure_;
std::unique_ptr<autoware_utils::LoggerLevelConfigure> logger_configure_;

//!< @brief extended kalman filter instance.
std::unique_ptr<EKFModule> ekf_module_;
Expand Down Expand Up @@ -188,8 +188,8 @@ class EKFLocalizer : public rclcpp::Node
const std_srvs::srv::SetBool::Request::SharedPtr req,
std_srvs::srv::SetBool::Response::SharedPtr res);

autoware::universe_utils::StopWatch<std::chrono::milliseconds> stop_watch_;
autoware::universe_utils::StopWatch<std::chrono::milliseconds> stop_watch_timer_cb_;
autoware_utils::StopWatch<std::chrono::milliseconds> stop_watch_;
autoware_utils::StopWatch<std::chrono::milliseconds> stop_watch_timer_cb_;

friend class EKFLocalizerTestSuite; // for test code
};
Expand Down
2 changes: 1 addition & 1 deletion localization/autoware_ekf_localizer/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_kalman_filter</depend>
<depend>autoware_localization_util</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_utils</depend>
<depend>diagnostic_msgs</depend>
<depend>fmt</depend>
<depend>geometry_msgs</depend>
Expand Down
4 changes: 2 additions & 2 deletions localization/autoware_ekf_localizer/src/covariance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,12 @@
#include "autoware/ekf_localizer/covariance.hpp"

#include "autoware/ekf_localizer/state_index.hpp"
#include "autoware/universe_utils/ros/msg_covariance.hpp"
#include "autoware_utils/ros/msg_covariance.hpp"

namespace autoware::ekf_localizer
{

using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;
using COV_IDX = autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;

std::array<double, 36> ekf_covariance_to_pose_message_covariance(const Matrix6d & P)
{
Expand Down
10 changes: 5 additions & 5 deletions localization/autoware_ekf_localizer/src/ekf_localizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,9 @@
#include "autoware/ekf_localizer/warning_message.hpp"
#include "autoware/localization_util/covariance_ellipse.hpp"

#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware/universe_utils/math/unit_conversion.hpp>
#include <autoware/universe_utils/ros/msg_covariance.hpp>
#include <autoware_utils/geometry/geometry.hpp>
#include <autoware_utils/math/unit_conversion.hpp>
#include <autoware_utils/ros/msg_covariance.hpp>
#include <rclcpp/duration.hpp>
#include <rclcpp/logging.hpp>

Expand Down Expand Up @@ -96,7 +96,7 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options)
std::shared_ptr<rclcpp::Node>(this, [](auto) {}));

ekf_module_ = std::make_unique<EKFModule>(warning_, params_);
logger_configure_ = std::make_unique<autoware::universe_utils::LoggerLevelConfigure>(this);
logger_configure_ = std::make_unique<autoware_utils::LoggerLevelConfigure>(this);
}

/*
Expand Down Expand Up @@ -361,7 +361,7 @@ void EKFLocalizer::publish_estimate_result(

/* publish tf */
const geometry_msgs::msg::TransformStamped transform_stamped =
autoware::universe_utils::pose2transform(current_ekf_pose, "base_link");
autoware_utils::pose2transform(current_ekf_pose, "base_link");
tf_br_->sendTransform(transform_stamped);
}

Expand Down
22 changes: 11 additions & 11 deletions localization/autoware_ekf_localizer/src/ekf_module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@
#include "autoware/ekf_localizer/state_transition.hpp"
#include "autoware/ekf_localizer/warning_message.hpp"

#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware/universe_utils/ros/msg_covariance.hpp>
#include <autoware_utils/geometry/geometry.hpp>
#include <autoware_utils/ros/msg_covariance.hpp>

#include <fmt/core.h>
#include <tf2/LinearMath/Quaternion.h>
Expand Down Expand Up @@ -75,7 +75,7 @@ void EKFModule::initialize(
x(IDX::VX) = 0.0;
x(IDX::WZ) = 0.0;

using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;
using COV_IDX = autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;
p(IDX::X, IDX::X) = initial_pose.pose.covariance[COV_IDX::X_X];
p(IDX::Y, IDX::Y) = initial_pose.pose.covariance[COV_IDX::Y_Y];
p(IDX::YAW, IDX::YAW) = initial_pose.pose.covariance[COV_IDX::YAW_YAW];
Expand All @@ -90,7 +90,7 @@ void EKFModule::initialize(

const double z = initial_pose.pose.pose.position.z;

const auto rpy = autoware::universe_utils::getRPY(initial_pose.pose.pose.orientation);
const auto rpy = autoware_utils::get_rpy(initial_pose.pose.pose.orientation);

const double z_var = initial_pose.pose.covariance[COV_IDX::Z_Z];
const double roll_var = initial_pose.pose.covariance[COV_IDX::ROLL_ROLL];
Expand Down Expand Up @@ -122,13 +122,13 @@ geometry_msgs::msg::PoseStamped EKFModule::get_current_pose(
Pose current_ekf_pose;
current_ekf_pose.header.frame_id = params_.pose_frame_id;
current_ekf_pose.header.stamp = current_time;
current_ekf_pose.pose.position = autoware::universe_utils::createPoint(x, y, z);
current_ekf_pose.pose.position = autoware_utils::create_point(x, y, z);
if (get_biased_yaw) {
current_ekf_pose.pose.orientation =
autoware::universe_utils::createQuaternionFromRPY(roll, pitch, biased_yaw);
autoware_utils::create_quaternion_from_rpy(roll, pitch, biased_yaw);
} else {
current_ekf_pose.pose.orientation =
autoware::universe_utils::createQuaternionFromRPY(roll, pitch, yaw);
autoware_utils::create_quaternion_from_rpy(roll, pitch, yaw);
}
return current_ekf_pose;
}
Expand All @@ -152,7 +152,7 @@ std::array<double, 36> EKFModule::get_current_pose_covariance() const
std::array<double, 36> cov =
ekf_covariance_to_pose_message_covariance(kalman_filter_.getLatestP());

using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;
using COV_IDX = autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;
cov[COV_IDX::Z_Z] = z_filter_.get_var();
cov[COV_IDX::ROLL_ROLL] = roll_filter_.get_var();
cov[COV_IDX::PITCH_PITCH] = pitch_filter_.get_var();
Expand Down Expand Up @@ -350,7 +350,7 @@ geometry_msgs::msg::PoseWithCovarianceStamped EKFModule::compensate_rph_with_del
pose_with_delay.pose.pose.orientation.z = curr_orientation.z();
pose_with_delay.pose.pose.orientation.w = curr_orientation.w();

Check warning on line 351 in localization/autoware_ekf_localizer/src/ekf_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/autoware_ekf_localizer/src/ekf_module.cpp#L348-L351

Added lines #L348 - L351 were not covered by tests

const auto rpy = autoware::universe_utils::getRPY(pose_with_delay.pose.pose.orientation);
const auto rpy = autoware_utils::get_rpy(pose_with_delay.pose.pose.orientation);
const double delta_z = kalman_filter_.getXelement(IDX::VX) * delay_time * std::sin(-rpy.y);
pose_with_delay.pose.pose.position.z += delta_z;

Check warning on line 355 in localization/autoware_ekf_localizer/src/ekf_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/autoware_ekf_localizer/src/ekf_module.cpp#L355

Added line #L355 was not covered by tests

Expand Down Expand Up @@ -443,9 +443,9 @@ void EKFModule::update_simple_1d_filters(
{
double z = pose.pose.pose.position.z;

Check warning on line 444 in localization/autoware_ekf_localizer/src/ekf_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/autoware_ekf_localizer/src/ekf_module.cpp#L444

Added line #L444 was not covered by tests

const auto rpy = autoware::universe_utils::getRPY(pose.pose.pose.orientation);
const auto rpy = autoware_utils::get_rpy(pose.pose.pose.orientation);

Check warning on line 446 in localization/autoware_ekf_localizer/src/ekf_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/autoware_ekf_localizer/src/ekf_module.cpp#L446

Added line #L446 was not covered by tests

using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;
using COV_IDX = autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;
double z_var = pose.pose.covariance[COV_IDX::Z_Z] * static_cast<double>(smoothing_step);
double roll_var = pose.pose.covariance[COV_IDX::ROLL_ROLL] * static_cast<double>(smoothing_step);

Check warning on line 450 in localization/autoware_ekf_localizer/src/ekf_module.cpp

View check run for this annotation

Codecov / codecov/patch

localization/autoware_ekf_localizer/src/ekf_module.cpp#L449-L450

Added lines #L449 - L450 were not covered by tests
double pitch_var =
Expand Down
6 changes: 3 additions & 3 deletions localization/autoware_ekf_localizer/src/measurement.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#include "autoware/ekf_localizer/measurement.hpp"

#include "autoware/ekf_localizer/state_index.hpp"
#include "autoware/universe_utils/ros/msg_covariance.hpp"
#include "autoware_utils/ros/msg_covariance.hpp"

namespace autoware::ekf_localizer
{
Expand All @@ -41,7 +41,7 @@ Eigen::Matrix3d pose_measurement_covariance(
const std::array<double, 36ul> & covariance, const size_t smoothing_step)
{
Eigen::Matrix3d r;
using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;
using COV_IDX = autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;
r << covariance.at(COV_IDX::X_X), covariance.at(COV_IDX::X_Y), covariance.at(COV_IDX::X_YAW),
covariance.at(COV_IDX::Y_X), covariance.at(COV_IDX::Y_Y), covariance.at(COV_IDX::Y_YAW),
covariance.at(COV_IDX::YAW_X), covariance.at(COV_IDX::YAW_Y), covariance.at(COV_IDX::YAW_YAW);
Expand All @@ -52,7 +52,7 @@ Eigen::Matrix2d twist_measurement_covariance(
const std::array<double, 36ul> & covariance, const size_t smoothing_step)
{
Eigen::Matrix2d r;
using COV_IDX = autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;
using COV_IDX = autoware_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX;
r << covariance.at(COV_IDX::X_X), covariance.at(COV_IDX::X_YAW), covariance.at(COV_IDX::YAW_X),
covariance.at(COV_IDX::YAW_YAW);
return r * static_cast<double>(smoothing_step);
Expand Down

0 comments on commit 75b4201

Please sign in to comment.