Skip to content

Commit 312b9c3

Browse files
committed
refactor(autoware_obstacle_stop_planner): prefix package and namespace with autoware
Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp>
1 parent 0256188 commit 312b9c3

32 files changed

+62
-62
lines changed

Diff for: .github/CODEOWNERS

+1-1
Original file line numberDiff line numberDiff line change
@@ -152,6 +152,7 @@ planning/autoware_freespace_planning_algorithms/** kosuke.takeuchi@tier4.jp taka
152152
planning/autoware_mission_planner/** isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp ryohsuke.mitsudome@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp
153153
planning/autoware_objects_of_interest_marker_interface/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp zulfaqar.azmi@tier4.jp
154154
planning/autoware_obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp
155+
planning/autoware_obstacle_stop_planner/** berkay@leodrive.ai bnk@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
155156
planning/autoware_path_optimizer/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp
156157
planning/autoware_path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp
157158
planning/autoware_planning_test_manager/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp
@@ -196,7 +197,6 @@ planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limi
196197
planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
197198
planning/motion_velocity_planner/autoware_motion_velocity_planner_common/** maxime.clement@tier4.jp
198199
planning/motion_velocity_planner/autoware_motion_velocity_planner_node/** maxime.clement@tier4.jp
199-
planning/obstacle_stop_planner/** berkay@leodrive.ai bnk@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
200200
planning/sampling_based_planner/autoware_bezier_sampler/** maxime.clement@tier4.jp
201201
planning/sampling_based_planner/autoware_frenet_planner/** maxime.clement@tier4.jp
202202
planning/sampling_based_planner/autoware_path_sampler/** maxime.clement@tier4.jp

Diff for: launch/tier4_planning_launch/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,7 @@
6565
<exec_depend>autoware_freespace_planner</exec_depend>
6666
<exec_depend>autoware_mission_planner</exec_depend>
6767
<exec_depend>autoware_obstacle_cruise_planner</exec_depend>
68+
<exec_depend>autoware_obstacle_stop_planner</exec_depend>
6869
<exec_depend>autoware_path_optimizer</exec_depend>
6970
<exec_depend>autoware_planning_evaluator</exec_depend>
7071
<exec_depend>autoware_planning_topic_converter</exec_depend>
@@ -74,7 +75,6 @@
7475
<exec_depend>autoware_surround_obstacle_checker</exec_depend>
7576
<exec_depend>autoware_velocity_smoother</exec_depend>
7677
<exec_depend>glog_component</exec_depend>
77-
<exec_depend>obstacle_stop_planner</exec_depend>
7878

7979
<test_depend>ament_lint_auto</test_depend>
8080
<test_depend>autoware_lint_common</test_depend>

Diff for: planning/.pages

+1-1
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ nav:
4848
- 'Obstacle Cruise Planner':
4949
- 'About Obstacle Cruise': planning/autoware_obstacle_cruise_planner
5050
- 'How to Debug': planning/autoware_obstacle_cruise_planner/docs/debug
51-
- 'Obstacle Stop Planner': planning/obstacle_stop_planner
51+
- 'Obstacle Stop Planner': planning/autoware_obstacle_stop_planner
5252
- 'Path Smoother':
5353
- 'About Path Smoother': planning/autoware_path_smoother
5454
- 'Elastic Band': planning/autoware_path_smoother/docs/eb

Diff for: planning/obstacle_stop_planner/CMakeLists.txt renamed to planning/autoware_obstacle_stop_planner/CMakeLists.txt

+10-10
Original file line numberDiff line numberDiff line change
@@ -1,32 +1,32 @@
11
cmake_minimum_required(VERSION 3.14)
2-
project(obstacle_stop_planner)
2+
project(autoware_obstacle_stop_planner)
33

44
find_package(autoware_cmake REQUIRED)
55
autoware_package()
66

77
find_package(Eigen3 REQUIRED)
88
find_package(PCL REQUIRED)
99

10-
ament_auto_add_library(obstacle_stop_planner SHARED
11-
src/debug_marker.cpp
12-
src/node.cpp
13-
src/planner_utils.cpp
14-
src/adaptive_cruise_control.cpp
10+
ament_auto_add_library(${PROJECT_NAME} SHARED
11+
DIRECTORY
12+
src
1513
)
1614

17-
target_include_directories(obstacle_stop_planner
15+
target_include_directories(${PROJECT_NAME}
1816
SYSTEM PUBLIC
1917
${PCL_INCLUDE_DIRS}
2018
${EIGEN3_INCLUDE_DIR}
19+
INTERFACE
20+
src
2121
)
2222

23-
target_link_libraries(obstacle_stop_planner
23+
target_link_libraries(${PROJECT_NAME}
2424
${PCL_LIBRARIES}
2525
)
2626

27-
rclcpp_components_register_node(obstacle_stop_planner
27+
rclcpp_components_register_node(${PROJECT_NAME}
2828
PLUGIN "motion_planning::ObstacleStopPlannerNode"
29-
EXECUTABLE obstacle_stop_planner_node
29+
EXECUTABLE ${PROJECT_NAME}_node
3030
)
3131

3232
if(BUILD_TESTING)

Diff for: planning/obstacle_stop_planner/package.xml renamed to planning/autoware_obstacle_stop_planner/package.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
11
<?xml version="1.0"?>
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
4-
<name>obstacle_stop_planner</name>
4+
<name>autoware_obstacle_stop_planner</name>
55
<version>0.1.0</version>
6-
<description>The obstacle_stop_planner package</description>
6+
<description>The autoware_obstacle_stop_planner package</description>
77

88
<maintainer email="satoshi.ota@tier4.jp">Satoshi Ota</maintainer>
99
<maintainer email="taiki.tanaka@tier4.jp">Taiki Tanaka</maintainer>

Diff for: planning/obstacle_stop_planner/src/adaptive_cruise_control.cpp renamed to planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp

+3-3
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 "obstacle_stop_planner/adaptive_cruise_control.hpp"
15+
#include "adaptive_cruise_control.hpp"
1616

1717
#include "autoware/motion_utils/trajectory/trajectory.hpp"
1818

@@ -122,7 +122,7 @@ constexpr double sign(const double value)
122122
}
123123
} // namespace
124124

125-
namespace motion_planning
125+
namespace autoware::motion_planning
126126
{
127127
AdaptiveCruiseController::AdaptiveCruiseController(
128128
rclcpp::Node * node, const double vehicle_width, const double vehicle_length,
@@ -786,4 +786,4 @@ double AdaptiveCruiseController::lowpass_filter(
786786
return gain * prev_value + (1.0 - gain) * current_value;
787787
}
788788

789-
} // namespace motion_planning
789+
} // namespace autoware::motion_planning

Diff for: planning/obstacle_stop_planner/include/obstacle_stop_planner/adaptive_cruise_control.hpp renamed to planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef OBSTACLE_STOP_PLANNER__ADAPTIVE_CRUISE_CONTROL_HPP_
16-
#define OBSTACLE_STOP_PLANNER__ADAPTIVE_CRUISE_CONTROL_HPP_
15+
#ifndef ADAPTIVE_CRUISE_CONTROL_HPP_
16+
#define ADAPTIVE_CRUISE_CONTROL_HPP_
1717

1818
#include <rclcpp/rclcpp.hpp>
1919

@@ -29,7 +29,7 @@
2929
#include <optional>
3030
#include <vector>
3131

32-
namespace motion_planning
32+
namespace autoware::motion_planning
3333
{
3434
using autoware_planning_msgs::msg::TrajectoryPoint;
3535
using TrajectoryPoints = std::vector<TrajectoryPoint>;
@@ -232,6 +232,6 @@ class AdaptiveCruiseController
232232
static constexpr unsigned int num_debug_values_ = 10;
233233
};
234234

235-
} // namespace motion_planning
235+
} // namespace autoware::motion_planning
236236

237-
#endif // OBSTACLE_STOP_PLANNER__ADAPTIVE_CRUISE_CONTROL_HPP_
237+
#endif // ADAPTIVE_CRUISE_CONTROL_HPP_

Diff for: planning/obstacle_stop_planner/src/debug_marker.cpp renamed to planning/autoware_obstacle_stop_planner/src/debug_marker.cpp

+3-3
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 "obstacle_stop_planner/debug_marker.hpp"
15+
#include "debug_marker.hpp"
1616

1717
#include <autoware/motion_utils/marker/marker_helper.hpp>
1818
#include <autoware/universe_utils/geometry/geometry.hpp>
@@ -38,7 +38,7 @@ using autoware::universe_utils::createMarkerColor;
3838
using autoware::universe_utils::createMarkerScale;
3939
using autoware::universe_utils::createPoint;
4040

41-
namespace motion_planning
41+
namespace autoware::motion_planning
4242
{
4343
ObstacleStopPlannerDebugNode::ObstacleStopPlannerDebugNode(
4444
rclcpp::Node * node, const double base_link2front)
@@ -542,4 +542,4 @@ VelocityFactorArray ObstacleStopPlannerDebugNode::makeVelocityFactorArray()
542542
return velocity_factor_array;
543543
}
544544

545-
} // namespace motion_planning
545+
} // namespace autoware::motion_planning

Diff for: planning/obstacle_stop_planner/include/obstacle_stop_planner/debug_marker.hpp renamed to planning/autoware_obstacle_stop_planner/src/debug_marker.hpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -11,8 +11,8 @@
1111
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
14-
#ifndef OBSTACLE_STOP_PLANNER__DEBUG_MARKER_HPP_
15-
#define OBSTACLE_STOP_PLANNER__DEBUG_MARKER_HPP_
14+
#ifndef DEBUG_MARKER_HPP_
15+
#define DEBUG_MARKER_HPP_
1616

1717
#include <rclcpp/rclcpp.hpp>
1818

@@ -34,7 +34,7 @@
3434
#include <Eigen/Core>
3535
#include <Eigen/Geometry>
3636
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
37-
namespace motion_planning
37+
namespace autoware::motion_planning
3838
{
3939

4040
using geometry_msgs::msg::Point;
@@ -154,6 +154,6 @@ class ObstacleStopPlannerDebugNode
154154
DebugValues debug_values_;
155155
};
156156

157-
} // namespace motion_planning
157+
} // namespace autoware::motion_planning
158158

159-
#endif // OBSTACLE_STOP_PLANNER__DEBUG_MARKER_HPP_
159+
#endif // DEBUG_MARKER_HPP_

Diff for: planning/obstacle_stop_planner/src/node.cpp renamed to planning/autoware_obstacle_stop_planner/src/node.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -20,8 +20,8 @@
2020
#include <vector>
2121

2222
#define EIGEN_MPL2_ONLY
23-
#include "obstacle_stop_planner/node.hpp"
24-
#include "obstacle_stop_planner/planner_utils.hpp"
23+
#include "node.hpp"
24+
#include "planner_utils.hpp"
2525

2626
#include <Eigen/Core>
2727
#include <Eigen/Geometry>
@@ -38,7 +38,7 @@
3838
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
3939
#endif
4040

41-
namespace motion_planning
41+
namespace autoware::motion_planning
4242
{
4343
using autoware::motion_utils::calcLongitudinalOffsetPose;
4444
using autoware::motion_utils::calcLongitudinalOffsetToSegment;
@@ -1601,7 +1601,7 @@ void ObstacleStopPlannerNode::publishDebugData(
16011601
debug_ptr_->publish();
16021602
}
16031603

1604-
} // namespace motion_planning
1604+
} // namespace autoware::motion_planning
16051605

16061606
#include <rclcpp_components/register_node_macro.hpp>
1607-
RCLCPP_COMPONENTS_REGISTER_NODE(motion_planning::ObstacleStopPlannerNode)
1607+
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::motion_planning::ObstacleStopPlannerNode)

Diff for: planning/obstacle_stop_planner/include/obstacle_stop_planner/node.hpp renamed to planning/autoware_obstacle_stop_planner/src/node.hpp

+8-8
Original file line numberDiff line numberDiff line change
@@ -12,14 +12,14 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef OBSTACLE_STOP_PLANNER__NODE_HPP_
16-
#define OBSTACLE_STOP_PLANNER__NODE_HPP_
15+
#ifndef NODE_HPP_
16+
#define NODE_HPP_
1717

18+
#include "adaptive_cruise_control.hpp"
1819
#include "autoware/universe_utils/ros/logger_level_configure.hpp"
1920
#include "autoware/universe_utils/system/stop_watch.hpp"
20-
#include "obstacle_stop_planner/adaptive_cruise_control.hpp"
21-
#include "obstacle_stop_planner/debug_marker.hpp"
22-
#include "obstacle_stop_planner/planner_data.hpp"
21+
#include "debug_marker.hpp"
22+
#include "planner_data.hpp"
2323

2424
#include <autoware/motion_utils/trajectory/conversion.hpp>
2525
#include <autoware/motion_utils/trajectory/trajectory.hpp>
@@ -62,7 +62,7 @@
6262
#include <utility>
6363
#include <vector>
6464

65-
namespace motion_planning
65+
namespace autoware::motion_planning
6666
{
6767

6868
namespace bg = boost::geometry;
@@ -319,6 +319,6 @@ class ObstacleStopPlannerNode : public rclcpp::Node
319319

320320
std::unique_ptr<autoware::universe_utils::PublishedTimePublisher> published_time_publisher_;
321321
};
322-
} // namespace motion_planning
322+
} // namespace autoware::motion_planning
323323

324-
#endif // OBSTACLE_STOP_PLANNER__NODE_HPP_
324+
#endif // NODE_HPP_

Diff for: planning/obstacle_stop_planner/include/obstacle_stop_planner/planner_data.hpp renamed to planning/autoware_obstacle_stop_planner/src/planner_data.hpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef OBSTACLE_STOP_PLANNER__PLANNER_DATA_HPP_
16-
#define OBSTACLE_STOP_PLANNER__PLANNER_DATA_HPP_
15+
#ifndef PLANNER_DATA_HPP_
16+
#define PLANNER_DATA_HPP_
1717

1818
#include <rclcpp/rclcpp.hpp>
1919

@@ -27,7 +27,7 @@
2727

2828
#include <map>
2929

30-
namespace motion_planning
30+
namespace autoware::motion_planning
3131
{
3232

3333
using diagnostic_msgs::msg::DiagnosticStatus;
@@ -282,6 +282,6 @@ struct PlannerData
282282
bool enable_adaptive_cruise{false};
283283
};
284284

285-
} // namespace motion_planning
285+
} // namespace autoware::motion_planning
286286

287-
#endif // OBSTACLE_STOP_PLANNER__PLANNER_DATA_HPP_
287+
#endif // PLANNER_DATA_HPP_

Diff for: planning/obstacle_stop_planner/src/planner_utils.cpp renamed to planning/autoware_obstacle_stop_planner/src/planner_utils.cpp

+3-3
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 "obstacle_stop_planner/planner_utils.hpp"
15+
#include "planner_utils.hpp"
1616

1717
#include <autoware/motion_utils/distance/distance.hpp>
1818
#include <autoware/motion_utils/trajectory/conversion.hpp>
@@ -29,7 +29,7 @@
2929

3030
#include <pcl_conversions/pcl_conversions.h>
3131

32-
namespace motion_planning
32+
namespace autoware::motion_planning
3333
{
3434

3535
using autoware::motion_utils::calcDecelDistWithJerkAndAccConstraints;
@@ -720,4 +720,4 @@ double calcObstacleMaxLength(const autoware_perception_msgs::msg::Shape & shape)
720720
throw std::logic_error("The shape type is not supported in obstacle_cruise_planner.");
721721
}
722722

723-
} // namespace motion_planning
723+
} // namespace autoware::motion_planning

Diff for: planning/obstacle_stop_planner/include/obstacle_stop_planner/planner_utils.hpp renamed to planning/autoware_obstacle_stop_planner/src/planner_utils.hpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -13,10 +13,10 @@
1313
// See the License for the specific language governing permissions and
1414
// limitations under the License.
1515

16-
#ifndef OBSTACLE_STOP_PLANNER__PLANNER_UTILS_HPP_
17-
#define OBSTACLE_STOP_PLANNER__PLANNER_UTILS_HPP_
16+
#ifndef PLANNER_UTILS_HPP_
17+
#define PLANNER_UTILS_HPP_
1818

19-
#include "obstacle_stop_planner/planner_data.hpp"
19+
#include "planner_data.hpp"
2020

2121
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
2222
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
@@ -33,7 +33,7 @@
3333
#include <utility>
3434
#include <vector>
3535

36-
namespace motion_planning
36+
namespace autoware::motion_planning
3737
{
3838

3939
namespace bg = boost::geometry;
@@ -149,6 +149,6 @@ double calcObstacleMaxLength(const autoware_perception_msgs::msg::Shape & shape)
149149

150150
rclcpp::SubscriptionOptions createSubscriptionOptions(rclcpp::Node * node_ptr);
151151

152-
} // namespace motion_planning
152+
} // namespace autoware::motion_planning
153153

154-
#endif // OBSTACLE_STOP_PLANNER__PLANNER_UTILS_HPP_
154+
#endif // PLANNER_UTILS_HPP_

Diff for: planning/obstacle_stop_planner/test/test_obstacle_stop_planner_node_interface.cpp renamed to planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp

+4-4
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 "obstacle_stop_planner/node.hpp"
15+
#include "node.hpp"
1616

1717
#include <ament_index_cpp/get_package_share_directory.hpp>
1818
#include <autoware_planning_test_manager/autoware_planning_test_manager.hpp>
@@ -22,8 +22,8 @@
2222

2323
#include <vector>
2424

25+
using autoware::motion_planning::ObstacleStopPlannerNode;
2526
using autoware::planning_test_manager::PlanningInterfaceTestManager;
26-
using motion_planning::ObstacleStopPlannerNode;
2727

2828
std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
2929
{
@@ -41,7 +41,7 @@ std::shared_ptr<ObstacleStopPlannerNode> generateNode()
4141
const auto autoware_test_utils_dir =
4242
ament_index_cpp::get_package_share_directory("autoware_test_utils");
4343
const auto obstacle_stop_planner_dir =
44-
ament_index_cpp::get_package_share_directory("obstacle_stop_planner");
44+
ament_index_cpp::get_package_share_directory("autoware_obstacle_stop_planner");
4545

4646
node_options.append_parameter_override("enable_slow_down", false);
4747

@@ -53,7 +53,7 @@ std::shared_ptr<ObstacleStopPlannerNode> generateNode()
5353
obstacle_stop_planner_dir + "/config/adaptive_cruise_control.param.yaml", "--params-file",
5454
obstacle_stop_planner_dir + "/config/obstacle_stop_planner.param.yaml"});
5555

56-
return std::make_shared<motion_planning::ObstacleStopPlannerNode>(node_options);
56+
return std::make_shared<ObstacleStopPlannerNode>(node_options);
5757
}
5858

5959
void publishMandatoryTopics(

0 commit comments

Comments
 (0)