Skip to content

Commit

Permalink
refactor(autoware_obstacle_stop_planner): prefix package and namespac…
Browse files Browse the repository at this point in the history
…e with autoware

Signed-off-by: Esteve Fernandez <[email protected]>
  • Loading branch information
esteve committed Jun 24, 2024
1 parent ef3cef1 commit 7dd4f1b
Show file tree
Hide file tree
Showing 32 changed files with 62 additions and 62 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,7 @@ planning/autoware_freespace_planning_algorithms/** [email protected] taka
planning/autoware_mission_planner/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
planning/autoware_objects_of_interest_marker_interface/** [email protected] [email protected] [email protected]
planning/autoware_obstacle_cruise_planner/** [email protected] [email protected] [email protected] [email protected]
planning/autoware_obstacle_stop_planner/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
planning/autoware_path_optimizer/** [email protected] [email protected] [email protected]
planning/autoware_path_smoother/** [email protected] [email protected]
planning/autoware_planning_test_manager/** [email protected] [email protected]
Expand Down Expand Up @@ -196,7 +197,6 @@ planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limi
planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/** [email protected] [email protected] [email protected] [email protected]
planning/motion_velocity_planner/autoware_motion_velocity_planner_common/** [email protected]
planning/motion_velocity_planner/autoware_motion_velocity_planner_node/** [email protected]
planning/obstacle_stop_planner/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
planning/sampling_based_planner/autoware_bezier_sampler/** [email protected]
planning/sampling_based_planner/autoware_frenet_planner/** [email protected]
planning/sampling_based_planner/autoware_path_sampler/** [email protected]
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_planning_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,7 @@
<exec_depend>autoware_freespace_planner</exec_depend>
<exec_depend>autoware_mission_planner</exec_depend>
<exec_depend>autoware_obstacle_cruise_planner</exec_depend>
<exec_depend>autoware_obstacle_stop_planner</exec_depend>
<exec_depend>autoware_path_optimizer</exec_depend>
<exec_depend>autoware_planning_evaluator</exec_depend>
<exec_depend>autoware_planning_topic_converter</exec_depend>
Expand All @@ -74,7 +75,6 @@
<exec_depend>autoware_surround_obstacle_checker</exec_depend>
<exec_depend>autoware_velocity_smoother</exec_depend>
<exec_depend>glog_component</exec_depend>
<exec_depend>obstacle_stop_planner</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
2 changes: 1 addition & 1 deletion planning/.pages
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ nav:
- 'Obstacle Cruise Planner':
- 'About Obstacle Cruise': planning/autoware_obstacle_cruise_planner
- 'How to Debug': planning/autoware_obstacle_cruise_planner/docs/debug
- 'Obstacle Stop Planner': planning/obstacle_stop_planner
- 'Obstacle Stop Planner': planning/autoware_obstacle_stop_planner
- 'Path Smoother':
- 'About Path Smoother': planning/autoware_path_smoother
- 'Elastic Band': planning/autoware_path_smoother/docs/eb
Expand Down
Original file line number Diff line number Diff line change
@@ -1,32 +1,32 @@
cmake_minimum_required(VERSION 3.14)
project(obstacle_stop_planner)
project(autoware_obstacle_stop_planner)

find_package(autoware_cmake REQUIRED)
autoware_package()

find_package(Eigen3 REQUIRED)
find_package(PCL REQUIRED)

ament_auto_add_library(obstacle_stop_planner SHARED
src/debug_marker.cpp
src/node.cpp
src/planner_utils.cpp
src/adaptive_cruise_control.cpp
ament_auto_add_library(${PROJECT_NAME} SHARED
DIRECTORY
src
)

target_include_directories(obstacle_stop_planner
target_include_directories(${PROJECT_NAME}
SYSTEM PUBLIC
${PCL_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIR}
INTERFACE
src
)

target_link_libraries(obstacle_stop_planner
target_link_libraries(${PROJECT_NAME}
${PCL_LIBRARIES}
)

rclcpp_components_register_node(obstacle_stop_planner
rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "motion_planning::ObstacleStopPlannerNode"
EXECUTABLE obstacle_stop_planner_node
EXECUTABLE ${PROJECT_NAME}_node
)

if(BUILD_TESTING)
Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>obstacle_stop_planner</name>
<name>autoware_obstacle_stop_planner</name>
<version>0.1.0</version>
<description>The obstacle_stop_planner package</description>
<description>The autoware_obstacle_stop_planner package</description>

<maintainer email="[email protected]">Satoshi Ota</maintainer>
<maintainer email="[email protected]">Taiki Tanaka</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "obstacle_stop_planner/adaptive_cruise_control.hpp"
#include "adaptive_cruise_control.hpp"

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

Expand Down Expand Up @@ -122,7 +122,7 @@ constexpr double sign(const double value)
}
} // namespace

namespace motion_planning
namespace autoware::motion_planning
{
AdaptiveCruiseController::AdaptiveCruiseController(
rclcpp::Node * node, const double vehicle_width, const double vehicle_length,
Expand Down Expand Up @@ -786,4 +786,4 @@ double AdaptiveCruiseController::lowpass_filter(
return gain * prev_value + (1.0 - gain) * current_value;
}

} // namespace motion_planning
} // namespace autoware::motion_planning
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef OBSTACLE_STOP_PLANNER__ADAPTIVE_CRUISE_CONTROL_HPP_
#define OBSTACLE_STOP_PLANNER__ADAPTIVE_CRUISE_CONTROL_HPP_
#ifndef ADAPTIVE_CRUISE_CONTROL_HPP_
#define ADAPTIVE_CRUISE_CONTROL_HPP_

#include <rclcpp/rclcpp.hpp>

Expand All @@ -29,7 +29,7 @@
#include <optional>
#include <vector>

namespace motion_planning
namespace autoware::motion_planning
{
using autoware_planning_msgs::msg::TrajectoryPoint;
using TrajectoryPoints = std::vector<TrajectoryPoint>;
Expand Down Expand Up @@ -232,6 +232,6 @@ class AdaptiveCruiseController
static constexpr unsigned int num_debug_values_ = 10;
};

} // namespace motion_planning
} // namespace autoware::motion_planning

#endif // OBSTACLE_STOP_PLANNER__ADAPTIVE_CRUISE_CONTROL_HPP_
#endif // ADAPTIVE_CRUISE_CONTROL_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "obstacle_stop_planner/debug_marker.hpp"
#include "debug_marker.hpp"

#include <autoware/motion_utils/marker/marker_helper.hpp>
#include <autoware/universe_utils/geometry/geometry.hpp>
Expand All @@ -38,7 +38,7 @@ using autoware::universe_utils::createMarkerColor;
using autoware::universe_utils::createMarkerScale;
using autoware::universe_utils::createPoint;

namespace motion_planning
namespace autoware::motion_planning
{
ObstacleStopPlannerDebugNode::ObstacleStopPlannerDebugNode(
rclcpp::Node * node, const double base_link2front)
Expand Down Expand Up @@ -542,4 +542,4 @@ VelocityFactorArray ObstacleStopPlannerDebugNode::makeVelocityFactorArray()
return velocity_factor_array;
}

} // namespace motion_planning
} // namespace autoware::motion_planning
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef OBSTACLE_STOP_PLANNER__DEBUG_MARKER_HPP_
#define OBSTACLE_STOP_PLANNER__DEBUG_MARKER_HPP_
#ifndef DEBUG_MARKER_HPP_
#define DEBUG_MARKER_HPP_

#include <rclcpp/rclcpp.hpp>

Expand All @@ -34,7 +34,7 @@
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
namespace motion_planning
namespace autoware::motion_planning
{

using geometry_msgs::msg::Point;
Expand Down Expand Up @@ -154,6 +154,6 @@ class ObstacleStopPlannerDebugNode
DebugValues debug_values_;
};

} // namespace motion_planning
} // namespace autoware::motion_planning

#endif // OBSTACLE_STOP_PLANNER__DEBUG_MARKER_HPP_
#endif // DEBUG_MARKER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@
#include <vector>

#define EIGEN_MPL2_ONLY
#include "obstacle_stop_planner/node.hpp"
#include "obstacle_stop_planner/planner_utils.hpp"
#include "node.hpp"
#include "planner_utils.hpp"

#include <Eigen/Core>
#include <Eigen/Geometry>
Expand All @@ -38,7 +38,7 @@
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

namespace motion_planning
namespace autoware::motion_planning
{
using autoware::motion_utils::calcLongitudinalOffsetPose;
using autoware::motion_utils::calcLongitudinalOffsetToSegment;
Expand Down Expand Up @@ -1601,7 +1601,7 @@ void ObstacleStopPlannerNode::publishDebugData(
debug_ptr_->publish();
}

} // namespace motion_planning
} // namespace autoware::motion_planning

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(motion_planning::ObstacleStopPlannerNode)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::motion_planning::ObstacleStopPlannerNode)
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef OBSTACLE_STOP_PLANNER__NODE_HPP_
#define OBSTACLE_STOP_PLANNER__NODE_HPP_
#ifndef NODE_HPP_
#define NODE_HPP_

#include "adaptive_cruise_control.hpp"
#include "autoware/universe_utils/ros/logger_level_configure.hpp"
#include "autoware/universe_utils/system/stop_watch.hpp"
#include "obstacle_stop_planner/adaptive_cruise_control.hpp"
#include "obstacle_stop_planner/debug_marker.hpp"
#include "obstacle_stop_planner/planner_data.hpp"
#include "debug_marker.hpp"
#include "planner_data.hpp"

#include <autoware/motion_utils/trajectory/conversion.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
Expand Down Expand Up @@ -62,7 +62,7 @@
#include <utility>
#include <vector>

namespace motion_planning
namespace autoware::motion_planning
{

namespace bg = boost::geometry;
Expand Down Expand Up @@ -319,6 +319,6 @@ class ObstacleStopPlannerNode : public rclcpp::Node

std::unique_ptr<autoware::universe_utils::PublishedTimePublisher> published_time_publisher_;
};
} // namespace motion_planning
} // namespace autoware::motion_planning

#endif // OBSTACLE_STOP_PLANNER__NODE_HPP_
#endif // NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef OBSTACLE_STOP_PLANNER__PLANNER_DATA_HPP_
#define OBSTACLE_STOP_PLANNER__PLANNER_DATA_HPP_
#ifndef PLANNER_DATA_HPP_
#define PLANNER_DATA_HPP_

#include <rclcpp/rclcpp.hpp>

Expand All @@ -27,7 +27,7 @@

#include <map>

namespace motion_planning
namespace autoware::motion_planning
{

using diagnostic_msgs::msg::DiagnosticStatus;
Expand Down Expand Up @@ -282,6 +282,6 @@ struct PlannerData
bool enable_adaptive_cruise{false};
};

} // namespace motion_planning
} // namespace autoware::motion_planning

#endif // OBSTACLE_STOP_PLANNER__PLANNER_DATA_HPP_
#endif // PLANNER_DATA_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "obstacle_stop_planner/planner_utils.hpp"
#include "planner_utils.hpp"

#include <autoware/motion_utils/distance/distance.hpp>
#include <autoware/motion_utils/trajectory/conversion.hpp>
Expand All @@ -29,7 +29,7 @@

#include <pcl_conversions/pcl_conversions.h>

namespace motion_planning
namespace autoware::motion_planning
{

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

} // namespace motion_planning
} // namespace autoware::motion_planning
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef OBSTACLE_STOP_PLANNER__PLANNER_UTILS_HPP_
#define OBSTACLE_STOP_PLANNER__PLANNER_UTILS_HPP_
#ifndef PLANNER_UTILS_HPP_
#define PLANNER_UTILS_HPP_

#include "obstacle_stop_planner/planner_data.hpp"
#include "planner_data.hpp"

#include <autoware/universe_utils/geometry/boost_geometry.hpp>
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
Expand All @@ -33,7 +33,7 @@
#include <utility>
#include <vector>

namespace motion_planning
namespace autoware::motion_planning
{

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

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

} // namespace motion_planning
} // namespace autoware::motion_planning

#endif // OBSTACLE_STOP_PLANNER__PLANNER_UTILS_HPP_
#endif // PLANNER_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "obstacle_stop_planner/node.hpp"
#include "node.hpp"

#include <ament_index_cpp/get_package_share_directory.hpp>
#include <autoware_planning_test_manager/autoware_planning_test_manager.hpp>
Expand All @@ -22,8 +22,8 @@

#include <vector>

using autoware::motion_planning::ObstacleStopPlannerNode;
using autoware::planning_test_manager::PlanningInterfaceTestManager;
using motion_planning::ObstacleStopPlannerNode;

std::shared_ptr<PlanningInterfaceTestManager> generateTestManager()
{
Expand All @@ -41,7 +41,7 @@ std::shared_ptr<ObstacleStopPlannerNode> generateNode()
const auto autoware_test_utils_dir =
ament_index_cpp::get_package_share_directory("autoware_test_utils");
const auto obstacle_stop_planner_dir =
ament_index_cpp::get_package_share_directory("obstacle_stop_planner");
ament_index_cpp::get_package_share_directory("autoware_obstacle_stop_planner");

node_options.append_parameter_override("enable_slow_down", false);

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

return std::make_shared<motion_planning::ObstacleStopPlannerNode>(node_options);
return std::make_shared<ObstacleStopPlannerNode>(node_options);
}

void publishMandatoryTopics(
Expand Down

0 comments on commit 7dd4f1b

Please sign in to comment.