Skip to content

Commit

Permalink
feat(planning_validator): add planning validator package
Browse files Browse the repository at this point in the history
Signed-off-by: Takamasa Horibe <[email protected]>

update

Signed-off-by: Takamasa Horibe <[email protected]>

update

Signed-off-by: Takamasa Horibe <[email protected]>

update

Signed-off-by: Takamasa Horibe <[email protected]>
  • Loading branch information
TakaHoribe committed Dec 31, 2022
1 parent b844cb1 commit 2fdb3ec
Show file tree
Hide file tree
Showing 12 changed files with 1,096 additions and 0 deletions.
46 changes: 46 additions & 0 deletions planning/planning_validator/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
cmake_minimum_required(VERSION 3.14)
project(planning_validator)

find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_add_library(planning_validator_helpers SHARED
src/utils.cpp
src/debug_marker.cpp
)

ament_auto_add_library(planning_validator_component SHARED
include/planning_validator/planning_validator.hpp
src/planning_validator.cpp
)
target_link_libraries(planning_validator_component planning_validator_helpers)

rclcpp_components_register_node(planning_validator_component
PLUGIN "planning_validator::PlanningValidator"
EXECUTABLE planning_validator_node
)

rosidl_generate_interfaces(
${PROJECT_NAME}
"msg/PlanningValidatorStatus.msg"
DEPENDENCIES builtin_interfaces
)

# to use a message defined in the same package
if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0)
rosidl_target_interfaces(planning_validator_component
${PROJECT_NAME} "rosidl_typesupport_cpp")
else()
rosidl_get_typesupport_target(
cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
target_link_libraries(planning_validator_component "${cpp_typesupport_target}")
endif()

if(BUILD_TESTING)
endif()

ament_auto_package(
INSTALL_TO_SHARE
config
launch
)
80 changes: 80 additions & 0 deletions planning/planning_validator/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
# Planning Error Monitor

## Purpose

`planning_error_monitor` checks a trajectory that if it has any invalid numerical values in its positions, twist and accel values. In addition, it also checks the distance between any two consecutive points and curvature value at a certain point. This package basically monitors if a trajectory, which is generated by planning module, has any unexpected errors.

## Inner-workings / Algorithms

![flow_chart_image](./media/flowchart.png)

### Point Value Checker (onTrajectoryPointValueChecker)

This function checks position, twist and accel values of all points on a trajectory. If they have `Nan` or `Infinity`, this function outputs error status.

### Interval Checker (onTrajectoryIntervalChecker)

This function computes interval distance between two consecutive points, and will output error messages if the distance is over the `interval_threshold`.

### Curvature Checker (onTrajectoryCurvatureChecker)

This function checks if the curvature at each point on a trajectory has an appropriate value. Calculation details are described in the following picture. First, we choose one point(green point in the picture) that are 1.0[m] behind the current point. Then we get a point(blue point in the picture) 1.0[m] ahead of the current point. Using these three points, we calculate the curvature by [this method](https://en.wikipedia.org/wiki/Menger_curvature).

### Relative Angle Checker (onTrajectoryRelativeAngleChecker)

This function checks if the relative angle at point1 generated from point2 and 3 on a trajectory has an appropriate value.

![curvature_calculation_diagram](./media/curvature_calculation_diagram.svg)

## Inputs / Outputs

### Input

| Name | Type | Description |
| -------------------- | ---------------------------------------- | -------------------------------------- |
| `~/input/trajectory` | `autoware_auto_planning_msgs/Trajectory` | Planned Trajectory by planning modules |

### Output

| Name | Type | Description |
| ---------------- | --------------------------------- | --------------------- |
| `/diagnostics` | `diagnostic_msgs/DiagnosticArray` | diagnostics outputs |
| `~/debug/marker` | `visualization_msgs/MarkerArray` | visualization markers |

## Parameters

| Name | Type | Description | Default value |
| :------------------------ | :------- | :------------------------------------ | :------------ |
| `error_interval` | `double` | Error Interval Distance Threshold [m] | 100.0 |
| `error_curvature` | `double` | Error Curvature Threshold | 1.0 |
| `error_sharp_angle` | `double` | Error Sharp Angle Threshold | $\pi$/4 |
| `ignore_too_close_points` | `double` | Ignore Too Close Distance Threshold | 0.005 |

## Visualization

When the trajectory error occurs, markers for visualization are published at the topic `~/debug/marker`.

- trajectory_interval: An error occurs when the distance between two points exceeds a certain large value. The two points where the error occurred will be visualized.
- trajectory_curvature: An error occurs when the curvature exceeds a certain large value. The three points used to calculate the curvature will be visualized.
- trajectory_relative_angle: An error occurs when the angle in the direction of the path point changes significantly. The three points used to calculate the relative angle will be visualized.

## Assumptions / Known limits

- It cannot compute curvature values at start and end points of the trajectory.
- If trajectory points are too close, curvature calculation might output incorrect values.

## Future extensions / Unimplemented parts

- Collision checker with obstacles may be implemented in the future.

## Error detection and handling

For the onsite validation, you can use the `invalid_trajectory_publisher` node. Please launch the node with the following command when the target trajectory is being published.

```bash
ros2 launch planning_error_monitor invalid_trajectory_publisher.launch.xml
```

This node subscribes the target trajectory, inserts the invalid point, and publishes it with the same name. The invalid trajectory is supposed to be detected by the `planning_error_monitor`.

Limitation: Once the `invalid_trajectory_publisher` receives the trajectory, it will turn off the subscriber. This is to prevent the trajectory from looping in the same node, therefore, only the one pattern of invalid trajectory is generated.
12 changes: 12 additions & 0 deletions planning/planning_validator/config/planning_validator.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
/**:
ros__parameters:
interval_threshold: 100.0
relative_angle_threshold: 10.0
curvature_threshold: 100.0
lateral_acc_threshold: 100.0
longitudinal_max_acc_threshold: 100.0
longitudinal_min_acc_threshold: -100.0
steering_threshold: 100.0
steering_rate_threshold: 100.0
velocity_deviation_threshold: 100.0
distance_deviation_threshold: 100.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
// Copyright 2021 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 PLANNING_VALIDATOR__DEBUG_MARKER_HPP_
#define PLANNING_VALIDATOR__DEBUG_MARKER_HPP_

#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <visualization_msgs/msg/marker.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <map>
#include <memory>
#include <string>
#include <vector>

class PlanningValidatorDebugPosePublisher
{
public:
explicit PlanningValidatorDebugPosePublisher(rclcpp::Node * node);

void pushPoseMarker(
const autoware_auto_planning_msgs::msg::TrajectoryPoint & p, const std::string & ns,
int id = 0);
void pushPoseMarker(const geometry_msgs::msg::Pose & pose, const std::string & ns, int id = 0);
void clearPoseMarker(const std::string & ns);
void publish();

private:
rclcpp::Node * node_;
visualization_msgs::msg::MarkerArray marker_array_;
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr debug_viz_pub_;
std::map<std::string, int> marker_id_;

int getMarkerId(const std::string & ns)
{
if (marker_id_.count(ns) == 0) {
marker_id_[ns] = 0.0;
}
return marker_id_[ns]++;
}

void clearMarkerId(const std::string & ns) { marker_id_[ns] = 0; }
};

#endif // PLANNING_VALIDATOR__DEBUG_MARKER_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,109 @@
// Copyright 2021 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 PLANNING_VALIDATOR__PLANNING_VALIDATOR_HPP_
#define PLANNING_VALIDATOR__PLANNING_VALIDATOR_HPP_

#include "planning_validator/debug_marker.hpp"
#include "planning_validator/msg/planning_validator_status.hpp"
#include "vehicle_info_util/vehicle_info_util.hpp"

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <diagnostic_msgs/msg/diagnostic_array.hpp>
#include <nav_msgs/msg/odometry.hpp>

#include <memory>
#include <string>

namespace planning_validator
{
using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
using diagnostic_updater::DiagnosticStatusWrapper;
using diagnostic_updater::Updater;
using nav_msgs::msg::Odometry;
using planning_validator::msg::PlanningValidatorStatus;

struct ValidationParams
{
double interval_threshold;
double relative_angle_threshold;
double curvature_threshold;
double lateral_acc_threshold;
double longitudinal_max_acc_threshold;
double longitudinal_min_acc_threshold;
double steering_threshold;
double steering_rate_threshold;
double velocity_deviation_threshold;
double distance_deviation_threshold;
};

class PlanningValidator : public rclcpp::Node
{
public:
explicit PlanningValidator(const rclcpp::NodeOptions & options);

void onTrajectory(const Trajectory::ConstSharedPtr msg);

private:
void setupDiag();
void setDiagStatus(
const std::string & name, const bool ok_condition, const std::string & error_msg);
void setupParameters();

bool isDataReady();

void validate(const Trajectory & trajectory);
bool checkValidFiniteValue(const Trajectory & trajectory);
bool checkValidInterval(const Trajectory & trajectory);
bool checkValidRelativeAngle(const Trajectory & trajectory);
bool checkValidCurvature(const Trajectory & trajectory);
bool checkValidLateralAcceleration(const Trajectory & trajectory);
bool checkValidMaxLongitudinalAcceleration(const Trajectory & trajectory);
bool checkValidMinLongitudinalAcceleration(const Trajectory & trajectory);
bool checkValidSteering(const Trajectory & trajectory);
bool checkValidSteeringRate(const Trajectory & trajectory);
bool checkValidVelocityDeviation(const Trajectory & trajectory);
bool checkValidDistanceDeviation(const Trajectory & trajectory);

void publishTrajectory();
void publishDebugInfo();

rclcpp::Subscription<Odometry>::SharedPtr sub_kinematics_;
rclcpp::Subscription<Trajectory>::SharedPtr sub_traj_;
rclcpp::Publisher<Trajectory>::SharedPtr pub_traj_;
rclcpp::Publisher<PlanningValidatorStatus>::SharedPtr pub_status_;

Updater diag_updater_{this};

PlanningValidatorStatus validation_status_;
ValidationParams validation_params_; // for thresholds

vehicle_info_util::VehicleInfo vehicle_info_;

bool isAllValid(const PlanningValidatorStatus & status);

Trajectory::ConstSharedPtr current_trajectory_;
Trajectory::ConstSharedPtr previous_published_trajectory_;

Odometry::ConstSharedPtr current_kinematics_;

std::shared_ptr<PlanningValidatorDebugPosePublisher> debugger_;
};
} // namespace planning_validator

#endif // PLANNING_VALIDATOR__PLANNING_VALIDATOR_HPP_
57 changes: 57 additions & 0 deletions planning/planning_validator/include/planning_validator/utils.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
// Copyright 2021 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 PLANNING_VALIDATOR__UTILS_HPP_
#define PLANNING_VALIDATOR__UTILS_HPP_

#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_planning_msgs/msg/trajectory.hpp>

#include <string>
#include <utility>
#include <vector>

namespace planning_validator
{
using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_auto_planning_msgs::msg::TrajectoryPoint;

std::pair<double, size_t> getMaxValAndIdx(const std::vector<double> & v);

std::pair<double, size_t> getMinValAndIdx(const std::vector<double> & v);

std::pair<double, size_t> getAbsMaxValAndIdx(const std::vector<double> & v);

Trajectory resampleTrajectory(const Trajectory & trajectory, const double min_interval);

std::vector<double> calcCurvature(const Trajectory & trajectory);

std::vector<double> calcIntervalDistance(const Trajectory & trajectory);

std::vector<double> calcLateralAcceleration(const Trajectory & trajectory);

std::vector<double> getLongitudinalAccArray(const Trajectory & trajectory);

std::vector<double> calcRelativeAngles(const Trajectory & trajectory);

std::vector<double> calcSteeringAngles(const Trajectory & trajectory, const double wheelbase);

std::vector<double> calcSteeringRates(const Trajectory & trajectory, const double wheelbase);

bool checkFinite(const TrajectoryPoint & point);

} // namespace planning_validator

#endif // PLANNING_VALIDATOR__UTILS_HPP_
13 changes: 13 additions & 0 deletions planning/planning_validator/launch/planning_validator.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<launch>
<arg name="planning_validator_param_path" default="$(find-pkg-share planning_validator)/config/planning_validator.param.yaml"/>

<node name="planning_validator" exec="planning_validator_node" pkg="planning_validator" output="screen">
<!-- load config a file -->
<param from="$(var planning_validator_param_path)"/>

<!-- remap topic name -->
<remap from="~/input/trajectory" to="/planning/scenario_planning/trajectory"/>
<remap from="~/input/kinematics" to="/localization/kinematic_state"/>
<remap from="~/output/trajectory" to="/planning/trajectory"/>
</node>
</launch>
Loading

0 comments on commit 2fdb3ec

Please sign in to comment.