Skip to content

Commit

Permalink
refactor(path_optimizer, velocity_smoother)!: prefix package and name…
Browse files Browse the repository at this point in the history
…space with autoware (autowarefoundation#7354)

* chore(autoware_velocity_smoother): update namespace

Signed-off-by: satoshi-ota <[email protected]>

* chore(autoware_path_optimizer): update namespace

Signed-off-by: satoshi-ota <[email protected]>

---------

Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota authored Jun 7, 2024
1 parent e6b56a4 commit 1f6c264
Show file tree
Hide file tree
Showing 47 changed files with 94 additions and 94 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@
<group>
<group if="$(eval &quot;'$(var motion_path_planner_type)' == 'path_optimizer'&quot;)">
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
<composable_node pkg="autoware_path_optimizer" plugin="autoware_path_optimizer::PathOptimizer" name="path_optimizer" namespace="">
<composable_node pkg="autoware_path_optimizer" plugin="autoware::path_optimizer::PathOptimizer" name="path_optimizer" namespace="">
<!-- topic remap -->
<remap from="~/input/path" to="path_smoother/path"/>
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
<!-- motion velocity smoother -->
<group>
<node_container pkg="rclcpp_components" exec="component_container" name="velocity_smoother_container" namespace="">
<composable_node pkg="autoware_velocity_smoother" plugin="autoware_velocity_smoother::VelocitySmootherNode" name="velocity_smoother" namespace="">
<composable_node pkg="autoware_velocity_smoother" plugin="autoware::velocity_smoother::VelocitySmootherNode" name="velocity_smoother" namespace="">
<param name="algorithm_type" value="$(var velocity_smoother_type)"/>
<param from="$(var common_param_path)"/>
<param from="$(var nearest_search_param_path)"/>
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_behavior_velocity_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -310,7 +310,7 @@ void BehaviorVelocityPlannerNode::onParam()
// constructed. It would be required if it was a callback. std::lock_guard<std::mutex>
// lock(mutex_);
planner_data_.velocity_smoother_ =
std::make_unique<autoware_velocity_smoother::AnalyticalJerkConstrainedSmoother>(*this);
std::make_unique<autoware::velocity_smoother::AnalyticalJerkConstrainedSmoother>(*this);
planner_data_.velocity_smoother_->setWheelBase(planner_data_.vehicle_info_.wheel_base_m);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ struct PlannerData
bool is_simulation = false;

// velocity smoother
std::shared_ptr<autoware_velocity_smoother::SmootherBase> velocity_smoother_;
std::shared_ptr<autoware::velocity_smoother::SmootherBase> velocity_smoother_;
// route handler
std::shared_ptr<route_handler::RouteHandler> route_handler_;
// parameters
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ bool smoothPath(
traj_smoothed.begin(), traj_resampled.begin(), traj_resampled.begin() + traj_resampled_closest);

if (external_v_limit) {
autoware_velocity_smoother::trajectory_utils::applyMaximumVelocityLimit(
autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit(
traj_resampled_closest, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed);
}
out_path = motion_utils::convertToPathWithLaneId<TrajectoryPoints>(traj_smoothed);
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_path_optimizer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ target_include_directories(autoware_path_optimizer

# register node
rclcpp_components_register_node(autoware_path_optimizer
PLUGIN "autoware_path_optimizer::PathOptimizer"
PLUGIN "autoware::path_optimizer::PathOptimizer"
EXECUTABLE path_optimizer_node
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <string>
#include <vector>

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
struct ReferencePoint;
struct Bounds;
Expand Down Expand Up @@ -153,6 +153,6 @@ struct EgoNearestParam
double dist_threshold{0.0};
double yaw_threshold{0.0};
};
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer

#endif // AUTOWARE_PATH_OPTIMIZER__COMMON_STRUCTS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,11 @@
#include <string>
#include <vector>

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
MarkerArray getDebugMarker(
const DebugData & debug_data,
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & optimized_points,
const vehicle_info_util::VehicleInfo & vehicle_info, const bool publish_extra_marker);
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer
#endif // AUTOWARE_PATH_OPTIMIZER__DEBUG_MARKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#include <utility>
#include <vector>

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
struct Bounds
{
Expand Down Expand Up @@ -308,5 +308,5 @@ class MPTOptimizer
size_t getNumberOfSlackVariables() const;
std::optional<double> calcNormalizedAvoidanceCost(const ReferencePoint & ref_point) const;
};
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer
#endif // AUTOWARE_PATH_OPTIMIZER__MPT_OPTIMIZER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
#include <string>
#include <vector>

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
class PathOptimizer : public rclcpp::Node
{
Expand Down Expand Up @@ -141,6 +141,6 @@ class PathOptimizer : public rclcpp::Node

std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
};
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer

#endif // AUTOWARE_PATH_OPTIMIZER__NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include <memory>
#include <vector>

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
class ReplanChecker
{
Expand Down Expand Up @@ -66,6 +66,6 @@ class ReplanChecker
bool isPathGoalChanged(
const PlannerData & planner_data, const std::vector<TrajectoryPoint> & prev_traj_points) const;
};
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer

#endif // AUTOWARE_PATH_OPTIMIZER__REPLAN_CHECKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <memory>
#include <vector>

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
struct ReferencePoint;

Expand Down Expand Up @@ -58,5 +58,5 @@ class StateEquationGenerator
std::unique_ptr<VehicleModelInterface> vehicle_model_ptr_;
mutable std::shared_ptr<TimeKeeper> time_keeper_ptr_;
};
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer
#endif // AUTOWARE_PATH_OPTIMIZER__STATE_EQUATION_GENERATOR_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
#include "tier4_debug_msgs/msg/string_stamped.hpp"
#include "visualization_msgs/msg/marker_array.hpp"

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
// std_msgs
using std_msgs::msg::Header;
Expand All @@ -45,6 +45,6 @@ using visualization_msgs::msg::MarkerArray;
// debug
using tier4_debug_msgs::msg::Float64Stamped;
using tier4_debug_msgs::msg::StringStamped;
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer

#endif // AUTOWARE_PATH_OPTIMIZER__TYPE_ALIAS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,13 @@
namespace tier4_autoware_utils
{
template <>
geometry_msgs::msg::Point getPoint(const autoware_path_optimizer::ReferencePoint & p);
geometry_msgs::msg::Point getPoint(const autoware::path_optimizer::ReferencePoint & p);

template <>
geometry_msgs::msg::Pose getPose(const autoware_path_optimizer::ReferencePoint & p);
geometry_msgs::msg::Pose getPose(const autoware::path_optimizer::ReferencePoint & p);
} // namespace tier4_autoware_utils

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
namespace geometry_utils
{
Expand All @@ -68,5 +68,5 @@ bool isOutsideDrivableAreaFromRectangleFootprint(
const vehicle_info_util::VehicleInfo & vehicle_info,
const bool use_footprint_polygon_for_outside_drivable_area_check);
} // namespace geometry_utils
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer
#endif // AUTOWARE_PATH_OPTIMIZER__UTILS__GEOMETRY_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -38,16 +38,16 @@
namespace tier4_autoware_utils
{
template <>
geometry_msgs::msg::Point getPoint(const autoware_path_optimizer::ReferencePoint & p);
geometry_msgs::msg::Point getPoint(const autoware::path_optimizer::ReferencePoint & p);

template <>
geometry_msgs::msg::Pose getPose(const autoware_path_optimizer::ReferencePoint & p);
geometry_msgs::msg::Pose getPose(const autoware::path_optimizer::ReferencePoint & p);

template <>
double getLongitudinalVelocity(const autoware_path_optimizer::ReferencePoint & p);
double getLongitudinalVelocity(const autoware::path_optimizer::ReferencePoint & p);
} // namespace tier4_autoware_utils

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
namespace trajectory_utils
{
Expand Down Expand Up @@ -214,5 +214,5 @@ void insertStopPoint(
std::vector<TrajectoryPoint> & traj_points, const geometry_msgs::msg::Pose & input_stop_pose,
const size_t stop_seg_idx);
} // namespace trajectory_utils
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer
#endif // AUTOWARE_PATH_OPTIMIZER__UTILS__TRAJECTORY_UTILS_HPP_
4 changes: 2 additions & 2 deletions planning/autoware_path_optimizer/src/debug_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@

#include "visualization_msgs/msg/marker_array.hpp"

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
using tier4_autoware_utils::appendMarkerArray;
using tier4_autoware_utils::createDefaultMarker;
Expand Down Expand Up @@ -432,4 +432,4 @@ MarkerArray getDebugMarker(

return marker_array;
}
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer
4 changes: 2 additions & 2 deletions planning/autoware_path_optimizer/src/mpt_optimizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
#include <optional>
#include <tuple>

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
namespace
{
Expand Down Expand Up @@ -1783,4 +1783,4 @@ std::optional<double> MPTOptimizer::calcNormalizedAvoidanceCost(
}
return std::clamp(-negative_avoidance_cost / mpt_param_.max_avoidance_cost, 0.0, 1.0);
}
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer
6 changes: 3 additions & 3 deletions planning/autoware_path_optimizer/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include <chrono>
#include <limits>

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
namespace
{
Expand Down Expand Up @@ -666,7 +666,7 @@ void PathOptimizer::publishDebugData(const Header & header) const

time_keeper_ptr_->toc(__func__, " ");
}
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer

#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(autoware_path_optimizer::PathOptimizer)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::path_optimizer::PathOptimizer)
4 changes: 2 additions & 2 deletions planning/autoware_path_optimizer/src/replan_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include <vector>

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
ReplanChecker::ReplanChecker(rclcpp::Node * node, const EgoNearestParam & ego_nearest_param)
: ego_nearest_param_(ego_nearest_param), logger_(node->get_logger().get_child("replan_checker"))
Expand Down Expand Up @@ -212,4 +212,4 @@ bool ReplanChecker::isPathGoalChanged(

return true;
}
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include "autoware_path_optimizer/mpt_optimizer.hpp"

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
// state equation: x = B u + W (u includes x_0)
// NOTE: Originally, x_t+1 = Ad x_t + Bd u + Wd.
Expand Down Expand Up @@ -69,4 +69,4 @@ Eigen::VectorXd StateEquationGenerator::predict(
{
return mat.B * U + mat.W;
}
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer
4 changes: 2 additions & 2 deletions planning/autoware_path_optimizer/src/utils/geometry_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
#include <stack>
#include <vector>

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
namespace bg = boost::geometry;
using tier4_autoware_utils::LinearRing2d;
Expand Down Expand Up @@ -207,4 +207,4 @@ bool isOutsideDrivableAreaFromRectangleFootprint(
return false;
}
} // namespace geometry_utils
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer
10 changes: 5 additions & 5 deletions planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,25 +36,25 @@
namespace tier4_autoware_utils
{
template <>
geometry_msgs::msg::Point getPoint(const autoware_path_optimizer::ReferencePoint & p)
geometry_msgs::msg::Point getPoint(const autoware::path_optimizer::ReferencePoint & p)
{
return p.pose.position;
}

template <>
geometry_msgs::msg::Pose getPose(const autoware_path_optimizer::ReferencePoint & p)
geometry_msgs::msg::Pose getPose(const autoware::path_optimizer::ReferencePoint & p)
{
return p.pose;
}

template <>
double getLongitudinalVelocity(const autoware_path_optimizer::ReferencePoint & p)
double getLongitudinalVelocity(const autoware::path_optimizer::ReferencePoint & p)
{
return p.longitudinal_velocity_mps;
}
} // namespace tier4_autoware_utils

namespace autoware_path_optimizer
namespace autoware::path_optimizer
{
namespace trajectory_utils
{
Expand Down Expand Up @@ -242,4 +242,4 @@ void insertStopPoint(
traj_points.insert(traj_points.begin() + stop_seg_idx + 1, additional_traj_point);
}
} // namespace trajectory_utils
} // namespace autoware_path_optimizer
} // namespace autoware::path_optimizer
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory)
planning_test_utils_dir + "/config/test_nearest_search.param.yaml", "--params-file",
path_optimizer_dir + "/config/path_optimizer.param.yaml"});

auto test_target_node = std::make_shared<autoware_path_optimizer::PathOptimizer>(node_options);
auto test_target_node = std::make_shared<autoware::path_optimizer::PathOptimizer>(node_options);

// publish necessary topics from test_manager
test_manager->publishOdometry(test_target_node, "path_optimizer/input/odometry");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ std::vector<TrajectoryPoint> OptimizationTrajectoryBasedCenterline::optimize_tra
const auto eb_path_smoother_ptr =
path_smoother::ElasticBandSmoother(create_node_options()).getElasticBandSmoother();
const auto mpt_optimizer_ptr =
autoware_path_optimizer::PathOptimizer(create_node_options()).getMPTOptimizer();
autoware::path_optimizer::PathOptimizer(create_node_options()).getMPTOptimizer();

// NOTE: The optimization is executed every valid_optimized_traj_points_num points.
constexpr int valid_optimized_traj_points_num = 10;
Expand Down Expand Up @@ -158,7 +158,7 @@ std::vector<TrajectoryPoint> OptimizationTrajectoryBasedCenterline::optimize_tra

// road collision avoidance by model predictive trajectory in the autoware_path_optimizer
// package
const autoware_path_optimizer::PlannerData planner_data{
const autoware::path_optimizer::PlannerData planner_data{
raw_path.header, smoothed_traj_points, raw_path.left_bound, raw_path.right_bound,
virtual_ego_pose};
const auto optimized_traj_points = mpt_optimizer_ptr->optimizeTrajectory(planner_data);
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_velocity_smoother/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ target_link_libraries(${PROJECT_NAME}_node
)

rclcpp_components_register_node(${PROJECT_NAME}_node
PLUGIN "autoware_velocity_smoother::VelocitySmootherNode"
PLUGIN "autoware::velocity_smoother::VelocitySmootherNode"
EXECUTABLE velocity_smoother_node
)

Expand Down
Loading

0 comments on commit 1f6c264

Please sign in to comment.