Skip to content

Commit

Permalink
fix namespaces
Browse files Browse the repository at this point in the history
Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
  • Loading branch information
danielsanchezaran committed Nov 14, 2024
1 parent 755b016 commit c033ce1
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -334,9 +334,9 @@ class AEB : public rclcpp::Node
autoware::universe_utils::InterProcessPollingSubscriber<Imu> sub_imu_{this, "~/input/imu"};
autoware::universe_utils::InterProcessPollingSubscriber<Trajectory> sub_predicted_traj_{
this, "~/input/predicted_trajectory"};
autoware_universe_utils::InterProcessPollingSubscriber<PredictedObjects> predicted_objects_sub_{
autoware::universe_utils::InterProcessPollingSubscriber<PredictedObjects> predicted_objects_sub_{
this, "~/input/objects"};
autoware_universe_utils::InterProcessPollingSubscriber<AutowareState> sub_autoware_state_{
autoware::universe_utils::InterProcessPollingSubscriber<AutowareState> sub_autoware_state_{
this, "/autoware/state"};
// publisher
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_obstacle_pointcloud_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,6 @@ using autoware::universe_utils::Polygon2d;
using autoware::universe_utils::Polygon3d;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_universe_utils::Point2d;
using autoware_universe_utils::Polygon2d;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::TransformStamped;
Expand Down
8 changes: 4 additions & 4 deletions control/autoware_autonomous_emergency_braking/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -755,7 +755,7 @@ void AEB::createObjectDataUsingPredictedObjects(
const auto current_p = [&]() {
const auto & first_point_of_path = ego_path.front();
const auto & p = first_point_of_path.position;
return autoware_universe_utils::createPoint(p.x, p.y, p.z);
return autoware::universe_utils::createPoint(p.x, p.y, p.z);
}();

auto get_object_tangent_velocity =
Expand All @@ -765,7 +765,7 @@ void AEB::createObjectDataUsingPredictedObjects(
predicted_object.kinematics.initial_twist_with_covariance.twist.linear.y);

const auto obj_yaw = tf2::getYaw(obj_pose.orientation);
const auto obj_idx = autoware_motion_utils::findNearestIndex(ego_path, obj_pose.position);
const auto obj_idx = autoware::motion_utils::findNearestIndex(ego_path, obj_pose.position);
const auto path_yaw = (current_ego_speed > 0.0)
? tf2::getYaw(ego_path.at(obj_idx).orientation)
: tf2::getYaw(ego_path.at(obj_idx).orientation) + M_PI;
Expand Down Expand Up @@ -796,9 +796,9 @@ void AEB::createObjectDataUsingPredictedObjects(
bool collision_points_added{false};
for (const auto & collision_point : collision_points_bg) {
const auto obj_position =
autoware_universe_utils::createPoint(collision_point.x(), collision_point.y(), 0.0);
autoware::universe_utils::createPoint(collision_point.x(), collision_point.y(), 0.0);
const double obj_arc_length =
autoware_motion_utils::calcSignedArcLength(ego_path, current_p, obj_position);
autoware::motion_utils::calcSignedArcLength(ego_path, current_p, obj_position);
if (std::isnan(obj_arc_length)) continue;

// If the object is behind the ego, we need to use the backward long offset. The
Expand Down
2 changes: 0 additions & 2 deletions control/autoware_autonomous_emergency_braking/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,6 @@ namespace autoware::motion::control::autonomous_emergency_braking::utils
using autoware::universe_utils::Polygon2d;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_universe_utils::Point2d;
using autoware_universe_utils::Polygon2d;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::TransformStamped;
Expand Down

0 comments on commit c033ce1

Please sign in to comment.