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

refactor(autoware_universe_utils)!: rename tier4_autoware_utils to autoware_universe_utils #52

Merged
merged 3 commits into from
Jun 18, 2024
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
2 changes: 1 addition & 1 deletion common/tier4_automatic_goal_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>
<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>geometry_msgs</depend>
<depend>libqt5-core</depend>
<depend>libqt5-gui</depend>
Expand All @@ -24,7 +25,6 @@
<depend>rviz_default_plugins</depend>
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tier4_autoware_utils</depend>
<depend>visualization_msgs</depend>
<depend>yaml-cpp</depend>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include "automatic_goal_panel.hpp"

#include <tier4_autoware_utils/ros/marker_helper.hpp>
#include <autoware/universe_utils/ros/marker_helper.hpp>

namespace rviz_plugins
{
Expand Down Expand Up @@ -439,9 +439,9 @@ void AutowareAutomaticGoalPanel::updateGoalIcon(const unsigned goal_index, const

void AutowareAutomaticGoalPanel::publishMarkers()
{
using tier4_autoware_utils::createDefaultMarker;
using tier4_autoware_utils::createMarkerColor;
using tier4_autoware_utils::createMarkerScale;
using autoware_universe_utils::createDefaultMarker;
using autoware_universe_utils::createMarkerColor;
using autoware_universe_utils::createMarkerScale;

MarkerArray text_array;
MarkerArray arrow_array;
Expand Down
2 changes: 1 addition & 1 deletion common/tier4_control_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_control_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>libqt5-core</depend>
<depend>libqt5-gui</depend>
Expand All @@ -19,7 +20,6 @@
<depend>rviz_common</depend>
<depend>rviz_default_plugins</depend>
<depend>rviz_ogre_vendor</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_control_msgs</depend>
<depend>tier4_external_api_msgs</depend>

Expand Down
2 changes: 1 addition & 1 deletion common/tier4_debug_tools/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,12 +11,12 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_planning_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>geometry_msgs</depend>
<depend>motion_utils</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tf2_ros</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_debug_msgs</depend>

<exec_depend>launch_ros</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ This plugin dispatches services to the "logger name" associated with "nodes" spe

!!! note

As of November 2023, in ROS 2 Humble, users are required to initiate a service server in the node to use this feature. (This might be integrated into ROS standards in the future.) For easy service server generation, you can use the [LoggerLevelConfigure](https://github.com/autowarefoundation/autoware.universe/blob/main/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/logger_level_configure.hpp) utility.
As of November 2023, in ROS 2 Humble, users are required to initiate a service server in the node to use this feature. (This might be integrated into ROS standards in the future.) For easy service server generation, you can use the [LoggerLevelConfigure](https://github.com/autowarefoundation/autoware.universe/blob/main/common/autoware_universe_utils/include/autoware_universe_utils/ros/logger_level_configure.hpp) utility.

## How to use the plugin

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ Planning:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
logger_name: behavior_path_planner.path_shifter
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
Expand Down Expand Up @@ -72,7 +72,7 @@ Planning:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner
logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner
logger_name: motion_utils

Expand All @@ -84,15 +84,15 @@ Planning:
- node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner
logger_name: planning.scenario_planning.lane_driving.motion_planning.obstacle_avoidance_planner
- node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner
logger_name: motion_utils

motion_velocity_smoother:
- node_name: /planning/scenario_planning/motion_velocity_smoother
logger_name: planning.scenario_planning.motion_velocity_smoother
- node_name: /planning/scenario_planning/motion_velocity_smoother
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/motion_velocity_smoother
logger_name: motion_utils

Expand All @@ -108,41 +108,41 @@ Control:
- node_name: /control/trajectory_follower/controller_node_exe
logger_name: control.trajectory_follower.controller_node_exe.lateral_controller
- node_name: /control/trajectory_follower/controller_node_exe
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils
- node_name: /control/trajectory_follower/controller_node_exe
logger_name: motion_utils

longitudinal_controller:
- node_name: /control/trajectory_follower/controller_node_exe
logger_name: control.trajectory_follower.controller_node_exe.longitudinal_controller
- node_name: /control/trajectory_follower/controller_node_exe
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils
- node_name: /control/trajectory_follower/controller_node_exe
logger_name: motion_utils

vehicle_cmd_gate:
- node_name: /control/vehicle_cmd_gate
logger_name: control.vehicle_cmd_gate
- node_name: /control/vehicle_cmd_gate
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils

# ============================================================
# common
# ============================================================

Common:
tier4_autoware_utils:
autoware_universe_utils:
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/lane_driving/motion_planning/path_smoother
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils
- node_name: /planning/scenario_planning/motion_velocity_smoother
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils
- node_name: /control/trajectory_follower/controller_node_exe
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils
- node_name: /control/vehicle_cmd_gate
logger_name: tier4_autoware_utils
logger_name: autoware_universe_utils
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,9 @@
#ifndef STOP_ACCEL_EVALUATOR__STOP_ACCEL_EVALUATOR_NODE_HPP_
#define STOP_ACCEL_EVALUATOR__STOP_ACCEL_EVALUATOR_NODE_HPP_

#include "autoware/universe_utils/ros/self_pose_listener.hpp"
#include "rclcpp/rclcpp.hpp"
#include "signal_processing/lowpass_filter_1d.hpp"
#include "tier4_autoware_utils/ros/self_pose_listener.hpp"

#include "geometry_msgs/msg/twist_stamped.hpp"
#include "nav_msgs/msg/odometry.hpp"
Expand All @@ -30,10 +30,10 @@

namespace stop_accel_evaluator
{
using autoware_universe_utils::SelfPoseListener;
using geometry_msgs::msg::TwistStamped;
using nav_msgs::msg::Odometry;
using sensor_msgs::msg::Imu;
using tier4_autoware_utils::SelfPoseListener;
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
using tier4_debug_msgs::msg::Float32Stamped;

Expand Down
2 changes: 1 addition & 1 deletion control/stop_accel_evaluator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,14 +10,14 @@

<build_depend>autoware_cmake</build_depend>

<depend>autoware_universe_utils</depend>
<depend>geometry_msgs</depend>
<depend>nav_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
<depend>signal_processing</depend>
<depend>std_msgs</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_debug_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "stop_accel_evaluator/stop_accel_evaluator_node.hpp"

#include "tier4_autoware_utils/math/constants.hpp"
#include "autoware/universe_utils/math/constants.hpp"

#include <algorithm>
#include <memory>
Expand Down Expand Up @@ -123,7 +123,7 @@ void StopAccelEvaluatorNode::calculateStopAccel()
const double pitch =
lpf_pitch_->filter(getPitchByQuaternion(current_pose_ptr->pose.orientation));

stop_accel_ = accel_sum / accel_num + tier4_autoware_utils::gravity *
stop_accel_ = accel_sum / accel_num + autoware_universe_utils::gravity *
std::sin(pitch); // consider removing gravity
stop_accel_with_gravity_ = accel_sum / accel_num; // not consider removing gravity

Expand Down
2 changes: 1 addition & 1 deletion driving_environment_analyzer/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_route_handler</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>geometry_msgs</depend>
<depend>interpolation</depend>
Expand All @@ -42,7 +43,6 @@
<depend>tf2_geometry_msgs</depend>
<depend>tf2_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_planning_msgs</depend>
<depend>tier4_rtc_msgs</depend>
<depend>visualization_msgs</depend>
Expand Down
12 changes: 6 additions & 6 deletions driving_environment_analyzer/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,9 +54,9 @@ std::vector<double> calcElevationAngle(const T & points)
}

for (size_t i = 0; i < points.size() - 1; ++i) {
const auto p1 = tier4_autoware_utils::getPoint(points.at(i));
const auto p2 = tier4_autoware_utils::getPoint(points.at(i + 1));
elevation_vec.at(i) = tier4_autoware_utils::calcElevationAngle(p1, p2);
const auto p1 = autoware_universe_utils::getPoint(points.at(i));
const auto p2 = autoware_universe_utils::getPoint(points.at(i + 1));
elevation_vec.at(i) = autoware_universe_utils::calcElevationAngle(p1, p2);
}
elevation_vec.at(elevation_vec.size() - 1) = elevation_vec.at(elevation_vec.size() - 2);

Expand All @@ -81,9 +81,9 @@ double calcElevationAngle(const lanelet::ConstLanelet & lane, const Pose & pose)

const size_t idx = motion_utils::findNearestSegmentIndex(points, pose.position);

const auto p1 = tier4_autoware_utils::getPoint(points.at(idx));
const auto p2 = tier4_autoware_utils::getPoint(points.at(idx + 1));
return tier4_autoware_utils::calcElevationAngle(p1, p2);
const auto p1 = autoware_universe_utils::getPoint(points.at(idx));
const auto p2 = autoware_universe_utils::getPoint(points.at(idx + 1));
return autoware_universe_utils::calcElevationAngle(p1, p2);
}

double getLaneWidth(const lanelet::ConstLanelet & lane)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef DEVIATION_ESTIMATOR__TIER4_AUTOWARE_UTILS_HPP_
#define DEVIATION_ESTIMATOR__TIER4_AUTOWARE_UTILS_HPP_
#ifndef DEVIATION_ESTIMATOR__AUTOWARE_UNIVERSE_UTILS_HPP_
#define DEVIATION_ESTIMATOR__AUTOWARE_UNIVERSE_UTILS_HPP_

#include "tier4_autoware_utils/geometry/geometry.hpp"
#include "tier4_autoware_utils/math/constants.hpp"
#include "tier4_autoware_utils/math/normalization.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "autoware/universe_utils/math/constants.hpp"
#include "autoware/universe_utils/math/normalization.hpp"

#include <tf2/utils.h>

// ToDo (kminoda): Replace these functions with the one from tier4_autoware_utils.
// ToDo (kminoda): Replace these functions with the one from autoware_universe_utils.
// Currently these functions are declared here since this tool has to be compatible with older
// version of Autoware.

Expand All @@ -38,11 +38,11 @@ template <class Pose1, class Pose2>
bool isDrivingForward(const Pose1 & src_pose, const Pose2 & dst_pose)
{
// check the first point direction
const double src_yaw = tf2::getYaw(tier4_autoware_utils::getPose(src_pose).orientation);
const double pose_direction_yaw = tier4_autoware_utils::calcAzimuthAngle(
tier4_autoware_utils::getPoint(src_pose), tier4_autoware_utils::getPoint(dst_pose));
return std::fabs(tier4_autoware_utils::normalizeRadian(src_yaw - pose_direction_yaw)) <
tier4_autoware_utils::pi / 2.0;
const double src_yaw = tf2::getYaw(autoware_universe_utils::getPose(src_pose).orientation);
const double pose_direction_yaw = autoware_universe_utils::calcAzimuthAngle(
autoware_universe_utils::getPoint(src_pose), autoware_universe_utils::getPoint(dst_pose));
return std::fabs(autoware_universe_utils::normalizeRadian(src_yaw - pose_direction_yaw)) <
autoware_universe_utils::pi / 2.0;
}

/**
Expand All @@ -56,8 +56,8 @@ template <class Point1, class Point2>
geometry_msgs::msg::Point calcInterpolatedPoint(
const Point1 & src, const Point2 & dst, const double ratio)
{
const auto src_point = tier4_autoware_utils::getPoint(src);
const auto dst_point = tier4_autoware_utils::getPoint(dst);
const auto src_point = autoware_universe_utils::getPoint(src);
const auto dst_point = autoware_universe_utils::getPoint(dst);

tf2::Vector3 src_vec;
src_vec.setX(src_point.x);
Expand Down Expand Up @@ -101,38 +101,40 @@ geometry_msgs::msg::Pose calcInterpolatedPose(

geometry_msgs::msg::Pose output_pose;
output_pose.position = calcInterpolatedPoint(
tier4_autoware_utils::getPoint(src_pose), tier4_autoware_utils::getPoint(dst_pose),
autoware_universe_utils::getPoint(src_pose), autoware_universe_utils::getPoint(dst_pose),
clamped_ratio);

if (set_orientation_from_position_direction) {
const double input_poses_dist = tier4_autoware_utils::calcDistance2d(
tier4_autoware_utils::getPoint(src_pose), tier4_autoware_utils::getPoint(dst_pose));
const double input_poses_dist = autoware_universe_utils::calcDistance2d(
autoware_universe_utils::getPoint(src_pose), autoware_universe_utils::getPoint(dst_pose));
const bool is_driving_forward = isDrivingForward(src_pose, dst_pose);

// Get orientation from interpolated point and src_pose
if ((is_driving_forward && clamped_ratio > 1.0 - (1e-6)) || input_poses_dist < 1e-3) {
output_pose.orientation = tier4_autoware_utils::getPose(dst_pose).orientation;
output_pose.orientation = autoware_universe_utils::getPose(dst_pose).orientation;
} else if (!is_driving_forward && clamped_ratio < 1e-6) {
output_pose.orientation = tier4_autoware_utils::getPose(src_pose).orientation;
output_pose.orientation = autoware_universe_utils::getPose(src_pose).orientation;
} else {
const auto & base_pose = is_driving_forward ? dst_pose : src_pose;
const double pitch = tier4_autoware_utils::calcElevationAngle(
tier4_autoware_utils::getPoint(output_pose), tier4_autoware_utils::getPoint(base_pose));
const double yaw = tier4_autoware_utils::calcAzimuthAngle(
tier4_autoware_utils::getPoint(output_pose), tier4_autoware_utils::getPoint(base_pose));
output_pose.orientation = tier4_autoware_utils::createQuaternionFromRPY(0.0, pitch, yaw);
const double pitch = autoware_universe_utils::calcElevationAngle(
autoware_universe_utils::getPoint(output_pose),
autoware_universe_utils::getPoint(base_pose));
const double yaw = autoware_universe_utils::calcAzimuthAngle(
autoware_universe_utils::getPoint(output_pose),
autoware_universe_utils::getPoint(base_pose));
output_pose.orientation = autoware_universe_utils::createQuaternionFromRPY(0.0, pitch, yaw);
}
} else {
// Get orientation by spherical linear interpolation
tf2::Transform src_tf;
tf2::Transform dst_tf;
tf2::fromMsg(tier4_autoware_utils::getPose(src_pose), src_tf);
tf2::fromMsg(tier4_autoware_utils::getPose(dst_pose), dst_tf);
tf2::fromMsg(autoware_universe_utils::getPose(src_pose), src_tf);
tf2::fromMsg(autoware_universe_utils::getPose(dst_pose), dst_tf);
const auto & quaternion = tf2::slerp(src_tf.getRotation(), dst_tf.getRotation(), clamped_ratio);
output_pose.orientation = tf2::toMsg(quaternion);
}

return output_pose;
}

#endif // DEVIATION_ESTIMATOR__TIER4_AUTOWARE_UTILS_HPP_
#endif // DEVIATION_ESTIMATOR__AUTOWARE_UNIVERSE_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,14 @@
#ifndef DEVIATION_ESTIMATOR__DEVIATION_ESTIMATOR_HPP_
#define DEVIATION_ESTIMATOR__DEVIATION_ESTIMATOR_HPP_

#include "autoware/universe_utils/ros/transform_listener.hpp"
#include "deviation_estimator/gyro_bias_module.hpp"
#include "deviation_estimator/logger.hpp"
#include "deviation_estimator/utils.hpp"
#include "deviation_estimator/validation_module.hpp"
#include "deviation_estimator/velocity_coef_module.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/utils.h"
#include "tier4_autoware_utils/ros/transform_listener.hpp"

#include "autoware_vehicle_msgs/msg/velocity_report.hpp"
#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
Expand Down Expand Up @@ -103,7 +103,7 @@ class DeviationEstimator : public rclcpp::Node
std::unique_ptr<VelocityCoefModule> vel_coef_module_;
std::unique_ptr<ValidationModule> validation_module_;

std::shared_ptr<tier4_autoware_utils::TransformListener> transform_listener_;
std::shared_ptr<autoware_universe_utils::TransformListener> transform_listener_;

void callback_pose_with_covariance(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg);

Expand Down
Loading
Loading