Skip to content

feat(autoware_planning_factor_interface): move to core #241

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 2 commits into from
Mar 10, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 11 additions & 0 deletions planning/autoware_planning_factor_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
cmake_minimum_required(VERSION 3.14)
project(autoware_planning_factor_interface)

find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_add_library(autoware_planning_factor_interface SHARED
DIRECTORY src
)

ament_auto_package()
66 changes: 66 additions & 0 deletions planning/autoware_planning_factor_interface/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
# autoware_planning_factor_interface

## Overview

The `PlanningFactorInterface` is a C++ class designed to facilitate the addition and publication of planning factors.

## Design

The `PlanningFactorInterface` class is designed to be lightweight and efficient, with the following key components:

- **Add:** Methods to add planning factors to the interface.

- **Publisher:** The class includes a publisher for `PlanningFactorArray` messages, which are used to distribute planning factors to other nodes in the system.

The design emphasizes flexibility and ease of use, allowing developers to quickly integrate new planning factors into autoware.

## Usage

### Including the Header

To use the `PlanningFactorInterface`, include the header file in your code:

```cpp
#include <autoware/planning_factor_interface/planning_factor_interface.hpp>
```

### Creating an Instance

Instantiate the `PlanningFactorInterface` by providing a node and a name for the factor module:

```cpp

class PlannerInterface
{
public:
virtual ~PlannerInterface() = default;
PlannerInterface(
rclcpp::Node & node, const LongitudinalInfo & longitudinal_info,
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info,
const EgoNearestParam & ego_nearest_param, const std::shared_ptr<DebugData> debug_data_ptr)
: planning_factor_interface_{std::make_unique<
autoware::planning_factor_interface::PlanningFactorInterface>(
&node, "obstacle_cruise_planner")},
```

code example from src/universe/autoware.universe/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp

### Adding Planning Factors

The `add` method can be used to add planning factors. Here's an example from src/universe/autoware.universe/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp.

```cpp
planning_factor_interface_->add(
stop_traj_points, planner_data.ego_pose, stop_traj_points.at(wall_idx).pose,
autoware_internal_planning_msgs::msg::PlanningFactor::NONE,
autoware_internal_planning_msgs::msg::SafetyFactorArray{});
```

### Publishing Factors

After adding planning factors, you can publish them by calling the `publish` method:

```cpp
// Publish the added factors
planning_factor_interface_->publish();
```
Original file line number Diff line number Diff line change
@@ -0,0 +1,242 @@
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// 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 AUTOWARE__PLANNING_FACTOR_INTERFACE__PLANNING_FACTOR_INTERFACE_HPP_
#define AUTOWARE__PLANNING_FACTOR_INTERFACE__PLANNING_FACTOR_INTERFACE_HPP_

#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_planning_msgs/msg/control_point.hpp>
#include <autoware_internal_planning_msgs/msg/path_point_with_lane_id.hpp>
#include <autoware_internal_planning_msgs/msg/planning_factor.hpp>
#include <autoware_internal_planning_msgs/msg/planning_factor_array.hpp>
#include <autoware_internal_planning_msgs/msg/safety_factor_array.hpp>
#include <autoware_planning_msgs/msg/path_point.hpp>
#include <autoware_planning_msgs/msg/trajectory_point.hpp>
#include <geometry_msgs/msg/pose.hpp>

#include <string>
#include <vector>

namespace autoware::planning_factor_interface
{

using autoware_internal_planning_msgs::msg::ControlPoint;
using autoware_internal_planning_msgs::msg::PlanningFactor;
using autoware_internal_planning_msgs::msg::PlanningFactorArray;
using autoware_internal_planning_msgs::msg::SafetyFactorArray;
using geometry_msgs::msg::Pose;

class PlanningFactorInterface
{
public:
PlanningFactorInterface(rclcpp::Node * node, const std::string & name)
: name_{name},
pub_factors_{
node->create_publisher<PlanningFactorArray>("/planning/planning_factors/" + name, 1)},
clock_{node->get_clock()}
{
}

/**
* @brief factor setter for single control point.
*
* @param path points.
* @param ego current pose.
* @param control point pose. (e.g. stop or slow down point pose)
* @param behavior of this planning factor.
* @param safety factor.
* @param driving direction.
* @param target velocity of the control point.
* @param shift length of the control point.
* @param detail information.
*/
template <class PointType>
void add(

Check warning on line 67 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L67

Added line #L67 was not covered by tests
const std::vector<PointType> & points, const Pose & ego_pose, const Pose & control_point_pose,
const uint16_t behavior, const SafetyFactorArray & safety_factors,
const bool is_driving_forward = true, const double velocity = 0.0,
const double shift_length = 0.0, const std::string & detail = "")
{
const auto distance = static_cast<float>(autoware::motion_utils::calcSignedArcLength(
points, ego_pose.position, control_point_pose.position));
add(

Check warning on line 75 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L73-L75

Added lines #L73 - L75 were not covered by tests
distance, control_point_pose, behavior, safety_factors, is_driving_forward, velocity,
shift_length, detail);
}

Check warning on line 78 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L78

Added line #L78 was not covered by tests

/**
* @brief factor setter for two control points (section).
*
* @param path points.
* @param ego current pose.
* @param control section start pose. (e.g. lane change start point pose)
* @param control section end pose. (e.g. lane change end point pose)
* @param behavior of this planning factor.
* @param safety factor.
* @param driving direction.
* @param target velocity of the control point.
* @param shift length of the control point.
* @param detail information.
*/
template <class PointType>
void add(

Check warning on line 95 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L95

Added line #L95 was not covered by tests
const std::vector<PointType> & points, const Pose & ego_pose, const Pose & start_pose,
const Pose & end_pose, const uint16_t behavior, const SafetyFactorArray & safety_factors,
const bool is_driving_forward = true, const double velocity = 0.0,
const double shift_length = 0.0, const std::string & detail = "")
{
const auto start_distance = static_cast<float>(
autoware::motion_utils::calcSignedArcLength(points, ego_pose.position, start_pose.position));
const auto end_distance = static_cast<float>(
autoware::motion_utils::calcSignedArcLength(points, ego_pose.position, end_pose.position));
add(

Check warning on line 105 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L101-L105

Added lines #L101 - L105 were not covered by tests
start_distance, end_distance, start_pose, end_pose, behavior, safety_factors,
is_driving_forward, velocity, shift_length, detail);
}

Check warning on line 108 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L108

Added line #L108 was not covered by tests

/**
* @brief factor setter for single control point.
*
* @param distance to control point.
* @param control point pose. (e.g. stop point pose)
* @param behavior of this planning factor.
* @param safety factor.
* @param driving direction.
* @param target velocity of the control point.
* @param shift length of the control point.
* @param detail information.
*/
void add(

Check warning on line 122 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L122

Added line #L122 was not covered by tests
const double distance, const Pose & control_point_pose, const uint16_t behavior,
const SafetyFactorArray & safety_factors, const bool is_driving_forward = true,
const double velocity = 0.0, const double shift_length = 0.0, const std::string & detail = "")
{
const auto control_point = autoware_internal_planning_msgs::build<ControlPoint>()
.pose(control_point_pose)
.velocity(velocity)
.shift_length(shift_length)
.distance(distance);

Check warning on line 131 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L127-L131

Added lines #L127 - L131 were not covered by tests

const auto factor = autoware_internal_planning_msgs::build<PlanningFactor>()
.module(name_)
.is_driving_forward(is_driving_forward)
.control_points({control_point})
.behavior(behavior)
.detail(detail)
.safety_factors(safety_factors);

Check warning on line 139 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L133-L139

Added lines #L133 - L139 were not covered by tests

factors_.push_back(factor);
}

Check warning on line 142 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L141-L142

Added lines #L141 - L142 were not covered by tests

/**
* @brief factor setter for two control points (section).
*
* @param distance to control section start point.
* @param distance to control section end point.
* @param control section start pose. (e.g. lane change start point pose)
* @param control section end pose. (e.g. lane change end point pose)
* @param behavior of this planning factor.
* @param safety factor.
* @param driving direction.
* @param target velocity of the control point.
* @param shift length of the control point.
* @param detail information.
*/
void add(

Check warning on line 158 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L158

Added line #L158 was not covered by tests
const double start_distance, const double end_distance, const Pose & start_pose,
const Pose & end_pose, const uint16_t behavior, const SafetyFactorArray & safety_factors,
const bool is_driving_forward = true, const double velocity = 0.0,
const double shift_length = 0.0, const std::string & detail = "")
{
const auto control_start_point = autoware_internal_planning_msgs::build<ControlPoint>()
.pose(start_pose)
.velocity(velocity)
.shift_length(shift_length)
.distance(start_distance);

Check warning on line 168 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L164-L168

Added lines #L164 - L168 were not covered by tests

const auto control_end_point = autoware_internal_planning_msgs::build<ControlPoint>()
.pose(end_pose)
.velocity(velocity)
.shift_length(shift_length)
.distance(end_distance);

Check warning on line 174 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L170-L174

Added lines #L170 - L174 were not covered by tests

const auto factor = autoware_internal_planning_msgs::build<PlanningFactor>()
.module(name_)
.is_driving_forward(is_driving_forward)
.control_points({control_start_point, control_end_point})
.behavior(behavior)
.detail(detail)
.safety_factors(safety_factors);

Check warning on line 182 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L176-L182

Added lines #L176 - L182 were not covered by tests

factors_.push_back(factor);
}

Check warning on line 185 in planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp#L184-L185

Added lines #L184 - L185 were not covered by tests

/**
* @brief publish planning factors.
*/
void publish()
{
PlanningFactorArray msg;
msg.header.frame_id = "map";
msg.header.stamp = clock_->now();
msg.factors = factors_;

pub_factors_->publish(msg);

factors_.clear();
}

private:
std::string name_;

rclcpp::Publisher<PlanningFactorArray>::SharedPtr pub_factors_;

rclcpp::Clock::SharedPtr clock_;

std::vector<PlanningFactor> factors_;
};

extern template void
PlanningFactorInterface::add<autoware_internal_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> &, const Pose &,
const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double,
const double, const std::string &);
extern template void PlanningFactorInterface::add<autoware_planning_msgs::msg::PathPoint>(
const std::vector<autoware_planning_msgs::msg::PathPoint> &, const Pose &, const Pose &,
const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double,
const std::string &);
extern template void PlanningFactorInterface::add<autoware_planning_msgs::msg::TrajectoryPoint>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> &, const Pose &, const Pose &,
const uint16_t behavior, const SafetyFactorArray &, const bool, const double, const double,
const std::string &);

extern template void
PlanningFactorInterface::add<autoware_internal_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<autoware_internal_planning_msgs::msg::PathPointWithLaneId> &, const Pose &,
const Pose &, const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool,
const double, const double, const std::string &);
extern template void PlanningFactorInterface::add<autoware_planning_msgs::msg::PathPoint>(
const std::vector<autoware_planning_msgs::msg::PathPoint> &, const Pose &, const Pose &,
const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double,
const double, const std::string &);
extern template void PlanningFactorInterface::add<autoware_planning_msgs::msg::TrajectoryPoint>(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> &, const Pose &, const Pose &,
const Pose &, const uint16_t behavior, const SafetyFactorArray &, const bool, const double,
const double, const std::string &);

} // namespace autoware::planning_factor_interface

#endif // AUTOWARE__PLANNING_FACTOR_INTERFACE__PLANNING_FACTOR_INTERFACE_HPP_
29 changes: 29 additions & 0 deletions planning/autoware_planning_factor_interface/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
<?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>autoware_planning_factor_interface</name>
<version>0.0.0</version>
<description>The autoware_planning_factor_interface package</description>
<maintainer email="satoshi.ota@tier4.jp">Satoshi Ota</maintainer>
<maintainer email="mamoru.sobue@tier4.jp">Mamoru Sobue</maintainer>
<license>Apache License 2.0</license>

<author email="satoshi.ota@tier4.jp">Satoshi Ota</author>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_utils</depend>
<depend>rclcpp</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Loading
Loading