Skip to content

Commit 8843c04

Browse files
author
github-actions
committed
feat(planning_debug_tools): replace autoware_universe_utils with specific autoware_utils sub-packages
Migrates all autoware_universe_utils usages in the planning_debug_tools package to the specific autoware_utils sub-packages, as part of the autoware_universe_utils deprecation tracked in autowarefoundation/autoware_universe#12376. Changes: - package.xml: - <depend>autoware_universe_utils</depend> removed - Added <depend>autoware_utils_geometry</depend> - Added <depend>autoware_utils_visualization</depend> - Header includes swapped: - autoware/universe_utils/geometry/geometry.hpp -> autoware_utils_geometry/geometry.hpp - autoware/universe_utils/ros/marker_helper.hpp -> autoware_utils_visualization/marker_helper.hpp - Geometry symbols (autoware_utils_geometry::): - calcDistance2d -> calc_distance2d - getPoint -> get_point - getRPY -> get_rpy - Visualization symbols (autoware_utils_visualization::): - appendMarkerArray -> append_marker_array - createDefaultMarker -> create_default_marker - createMarkerColor -> create_marker_color - createMarkerScale -> create_marker_scale Both the 'using' declarations and the bare call sites they introduced have been updated to the new snake_case names. Note: The tf2::Matrix3x3::getRPY method call in perception_replayer/utils.hpp is an unrelated tf2 API and is intentionally left unchanged. Signed-off-by: github-actions <github-actions@github.com>
1 parent 700c544 commit 8843c04

4 files changed

Lines changed: 29 additions & 28 deletions

File tree

planning/planning_debug_tools/include/planning_debug_tools/trajectory_analyzer.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
1616
#define PLANNING_DEBUG_TOOLS__TRAJECTORY_ANALYZER_HPP_
1717

1818
#include "autoware/motion_utils/trajectory/trajectory.hpp"
19-
#include "autoware/universe_utils/geometry/geometry.hpp"
19+
#include <autoware_utils_geometry/geometry.hpp>
2020
#include "planning_debug_tools/msg/trajectory_debug_info.hpp"
2121
#include "planning_debug_tools/util.hpp"
2222
#include "rclcpp/rclcpp.hpp"

planning/planning_debug_tools/include/planning_debug_tools/util.hpp

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
1616
#define PLANNING_DEBUG_TOOLS__UTIL_HPP_
1717

1818
#include "autoware/motion_utils/trajectory/trajectory.hpp"
19-
#include "autoware/universe_utils/geometry/geometry.hpp"
19+
#include <autoware_utils_geometry/geometry.hpp>
2020
#include "rclcpp/rclcpp.hpp"
2121

2222
#include "autoware_internal_planning_msgs/msg/path_with_lane_id.hpp"
@@ -28,9 +28,9 @@
2828
namespace planning_debug_tools
2929
{
3030

31-
using autoware::universe_utils::calcDistance2d;
32-
using autoware::universe_utils::getPoint;
33-
using autoware::universe_utils::getRPY;
31+
using autoware_utils_geometry::calc_distance2d;
32+
using autoware_utils_geometry::get_point;
33+
using autoware_utils_geometry::get_rpy;
3434
using autoware_internal_planning_msgs::msg::PathPointWithLaneId;
3535
using autoware_planning_msgs::msg::PathPoint;
3636
using autoware_planning_msgs::msg::TrajectoryPoint;
@@ -50,15 +50,15 @@ double getVelocity(const TrajectoryPoint & p)
5050

5151
double getYaw(const PathPoint & p)
5252
{
53-
return getRPY(p.pose.orientation).z;
53+
return get_rpy(p.pose.orientation).z;
5454
}
5555
double getYaw(const PathPointWithLaneId & p)
5656
{
57-
return getRPY(p.point.pose.orientation).z;
57+
return get_rpy(p.point.pose.orientation).z;
5858
}
5959
double getYaw(const TrajectoryPoint & p)
6060
{
61-
return getRPY(p.pose.orientation).z;
61+
return get_rpy(p.pose.orientation).z;
6262
}
6363

6464
template <class T>
@@ -88,7 +88,7 @@ inline std::vector<double> getAccelerationArray(const T & points)
8888
const auto & prev_point = points.at(i);
8989
const auto & next_point = points.at(i + 1);
9090

91-
const double delta_s = autoware::universe_utils::calcDistance2d(prev_point, next_point);
91+
const double delta_s = autoware_utils_geometry::calc_distance2d(prev_point, next_point);
9292
if (delta_s == 0.0) {
9393
segment_wise_a_arr.push_back(0.0);
9494
} else {
@@ -125,7 +125,7 @@ std::vector<double> calcPathArcLengthArray(const T & points, const double offset
125125
out.push_back(offset);
126126
double sum = offset;
127127
for (size_t i = 1; i < points.size(); ++i) {
128-
sum += calcDistance2d(getPoint(points.at(i)), getPoint(points.at(i - 1)));
128+
sum += calc_distance2d(get_point(points.at(i)), get_point(points.at(i - 1)));
129129
out.push_back(sum);
130130
}
131131
return out;

planning/planning_debug_tools/package.xml

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,8 @@
2727
<depend>autoware_motion_utils</depend>
2828
<depend>autoware_perception_msgs</depend>
2929
<depend>autoware_planning_msgs</depend>
30-
<depend>autoware_universe_utils</depend>
30+
<depend>autoware_utils_geometry</depend>
31+
<depend>autoware_utils_visualization</depend>
3132
<depend>geometry_msgs</depend>
3233
<depend>libqt5-core</depend>
3334
<depend>libqt5-gui</depend>

planning/planning_debug_tools/src/stop_reason_visualizer.cpp

Lines changed: 17 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include <autoware/universe_utils/ros/marker_helper.hpp>
15+
#include <autoware_utils_visualization/marker_helper.hpp>
1616
#include <rclcpp/rclcpp.hpp>
1717

1818
#include <std_msgs/msg/header.hpp>
@@ -49,10 +49,10 @@ class StopReasonVisualizerNode : public rclcpp::Node
4949
private:
5050
void onStopReasonArray(const StopReasonArray::ConstSharedPtr msg)
5151
{
52-
using autoware::universe_utils::appendMarkerArray;
53-
using autoware::universe_utils::createDefaultMarker;
54-
using autoware::universe_utils::createMarkerColor;
55-
using autoware::universe_utils::createMarkerScale;
52+
using autoware_utils_visualization::append_marker_array;
53+
using autoware_utils_visualization::create_default_marker;
54+
using autoware_utils_visualization::create_marker_color;
55+
using autoware_utils_visualization::create_marker_scale;
5656

5757
MarkerArray all_marker_array;
5858
const auto header = msg->header;
@@ -69,53 +69,53 @@ class StopReasonVisualizerNode : public rclcpp::Node
6969
const auto stop_factor_point = stop_factor.stop_factor_points.front();
7070
// base stop pose marker
7171
{
72-
auto stop_point_marker = createDefaultMarker(
72+
auto stop_point_marker = create_default_marker(
7373
"map", current_time, prefix + ":stop_factor_point", id, Marker::SPHERE,
74-
createMarkerScale(0.25, 0.25, 0.25), createMarkerColor(1.0, 0.0, 0.0, 0.999));
74+
create_marker_scale(0.25, 0.25, 0.25), create_marker_color(1.0, 0.0, 0.0, 0.999));
7575
stop_point_marker.pose.position = stop_factor_point;
7676
marker_array.markers.emplace_back(stop_point_marker);
7777
}
7878
// attention ! marker
7979
{
80-
auto attention_text_marker = createDefaultMarker(
80+
auto attention_text_marker = create_default_marker(
8181
"map", current_time, prefix + ":attention text", id,
82-
visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 1.0),
83-
createMarkerColor(1.0, 1.0, 1.0, 0.999));
82+
visualization_msgs::msg::Marker::TEXT_VIEW_FACING, create_marker_scale(0.0, 0.0, 1.0),
83+
create_marker_color(1.0, 1.0, 1.0, 0.999));
8484
attention_text_marker.pose.position = stop_factor_point;
8585
attention_text_marker.pose.position.z += offset_z;
8686
attention_text_marker.text = "!";
8787
marker_array.markers.emplace_back(attention_text_marker);
8888
}
8989
// point to pose
9090
{
91-
auto stop_to_pose_marker = createDefaultMarker(
91+
auto stop_to_pose_marker = create_default_marker(
9292
"map", current_time, prefix + ":stop_to_pose", id, Marker::LINE_STRIP,
93-
createMarkerScale(0.02, 0.0, 0.0), createMarkerColor(0.0, 1.0, 1.0, 0.999));
93+
create_marker_scale(0.02, 0.0, 0.0), create_marker_color(0.0, 1.0, 1.0, 0.999));
9494
stop_to_pose_marker.points.emplace_back(stop_factor.stop_factor_points.front());
9595
stop_to_pose_marker.points.emplace_back(stop_factor.stop_pose.position);
9696
marker_array.markers.emplace_back(stop_to_pose_marker);
9797
}
9898
// point to pose
9999
{
100-
auto stop_pose_marker = createDefaultMarker(
100+
auto stop_pose_marker = create_default_marker(
101101
"map", current_time, prefix + ":stop_pose", id, Marker::ARROW,
102-
createMarkerScale(0.4, 0.2, 0.2), createMarkerColor(1.0, 0.0, 0.0, 0.999));
102+
create_marker_scale(0.4, 0.2, 0.2), create_marker_color(1.0, 0.0, 0.0, 0.999));
103103
stop_pose_marker.pose = stop_factor.stop_pose;
104104
marker_array.markers.emplace_back(stop_pose_marker);
105105
}
106106
// add view distance text
107107
{
108-
auto reason_text_marker = createDefaultMarker(
108+
auto reason_text_marker = create_default_marker(
109109
"map", current_time, prefix + ":reason", id, Marker::TEXT_VIEW_FACING,
110-
createMarkerScale(0.0, 0.0, 0.2), createMarkerColor(1.0, 1.0, 1.0, 0.999));
110+
create_marker_scale(0.0, 0.0, 0.2), create_marker_color(1.0, 1.0, 1.0, 0.999));
111111
reason_text_marker.pose = stop_factor.stop_pose;
112112
reason_text_marker.text = prefix;
113113
marker_array.markers.emplace_back(reason_text_marker);
114114
}
115115
id++;
116116
}
117117
if (!marker_array.markers.empty())
118-
appendMarkerArray(marker_array, &all_marker_array, current_time);
118+
append_marker_array(marker_array, &all_marker_array, current_time);
119119
}
120120
pub_stop_reasons_marker_->publish(all_marker_array);
121121
}

0 commit comments

Comments
 (0)