Skip to content

Commit 40b2e28

Browse files
solve merge issues
Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent 7684b56 commit 40b2e28

File tree

4 files changed

+8
-10
lines changed

4 files changed

+8
-10
lines changed

control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -328,9 +328,9 @@ class AEB : public rclcpp::Node
328328
autoware::universe_utils::InterProcessPollingSubscriber<Imu> sub_imu_{this, "~/input/imu"};
329329
autoware::universe_utils::InterProcessPollingSubscriber<Trajectory> sub_predicted_traj_{
330330
this, "~/input/predicted_trajectory"};
331-
autoware_universe_utils::InterProcessPollingSubscriber<PredictedObjects> predicted_objects_sub_{
331+
autoware::universe_utils::InterProcessPollingSubscriber<PredictedObjects> predicted_objects_sub_{
332332
this, "~/input/objects"};
333-
autoware_universe_utils::InterProcessPollingSubscriber<AutowareState> sub_autoware_state_{
333+
autoware::universe_utils::InterProcessPollingSubscriber<AutowareState> sub_autoware_state_{
334334
this, "/autoware/state"};
335335
// publisher
336336
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_obstacle_pointcloud_;

control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -37,11 +37,10 @@
3737

3838
namespace autoware::motion::control::autonomous_emergency_braking::utils
3939
{
40+
using autoware::universe_utils::Point2d;
4041
using autoware::universe_utils::Polygon2d;
4142
using autoware_perception_msgs::msg::PredictedObject;
4243
using autoware_perception_msgs::msg::PredictedObjects;
43-
using autoware_universe_utils::Point2d;
44-
using autoware_universe_utils::Polygon2d;
4544
using geometry_msgs::msg::Point;
4645
using geometry_msgs::msg::Pose;
4746
using geometry_msgs::msg::TransformStamped;

control/autoware_autonomous_emergency_braking/src/node.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -700,7 +700,7 @@ void AEB::createObjectDataUsingPredictedObjects(
700700
const auto current_p = [&]() {
701701
const auto & first_point_of_path = ego_path.front();
702702
const auto & p = first_point_of_path.position;
703-
return autoware_universe_utils::createPoint(p.x, p.y, p.z);
703+
return autoware::universe_utils::createPoint(p.x, p.y, p.z);
704704
}();
705705

706706
auto get_object_tangent_velocity =
@@ -710,7 +710,7 @@ void AEB::createObjectDataUsingPredictedObjects(
710710
predicted_object.kinematics.initial_twist_with_covariance.twist.linear.y);
711711

712712
const auto obj_yaw = tf2::getYaw(obj_pose.orientation);
713-
const auto obj_idx = autoware_motion_utils::findNearestIndex(ego_path, obj_pose.position);
713+
const auto obj_idx = motion_utils::findNearestIndex(ego_path, obj_pose.position);
714714
const auto path_yaw = (current_ego_speed > 0.0)
715715
? tf2::getYaw(ego_path.at(obj_idx).orientation)
716716
: tf2::getYaw(ego_path.at(obj_idx).orientation) + M_PI;
@@ -741,9 +741,9 @@ void AEB::createObjectDataUsingPredictedObjects(
741741
bool collision_points_added{false};
742742
for (const auto & collision_point : collision_points_bg) {
743743
const auto obj_position =
744-
autoware_universe_utils::createPoint(collision_point.x(), collision_point.y(), 0.0);
744+
autoware::universe_utils::createPoint(collision_point.x(), collision_point.y(), 0.0);
745745
const double obj_arc_length =
746-
autoware_motion_utils::calcSignedArcLength(ego_path, current_p, obj_position);
746+
motion_utils::calcSignedArcLength(ego_path, current_p, obj_position);
747747
if (std::isnan(obj_arc_length)) continue;
748748

749749
// If the object is behind the ego, we need to use the backward long offset. The

control/autoware_autonomous_emergency_braking/src/utils.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -18,11 +18,10 @@
1818

1919
namespace autoware::motion::control::autonomous_emergency_braking::utils
2020
{
21+
using autoware::universe_utils::Point2d;
2122
using autoware::universe_utils::Polygon2d;
2223
using autoware_perception_msgs::msg::PredictedObject;
2324
using autoware_perception_msgs::msg::PredictedObjects;
24-
using autoware_universe_utils::Point2d;
25-
using autoware_universe_utils::Polygon2d;
2625
using geometry_msgs::msg::Point;
2726
using geometry_msgs::msg::Pose;
2827
using geometry_msgs::msg::TransformStamped;

0 commit comments

Comments
 (0)