No version for distro humble. Known supported distros are highlighted in the buttons above.
No version for distro jazzy. Known supported distros are highlighted in the buttons above.
No version for distro kilted. Known supported distros are highlighted in the buttons above.
No version for distro rolling. Known supported distros are highlighted in the buttons above.

autoware_motion_utils package from autoware_core repo

autoware_core autoware_component_interface_specs autoware_geography_utils autoware_global_parameter_loader autoware_interpolation autoware_kalman_filter autoware_lanelet2_utils autoware_motion_utils autoware_node autoware_object_recognition_utils autoware_osqp_interface autoware_point_types autoware_qp_interface autoware_signal_processing autoware_trajectory autoware_vehicle_info_utils autoware_core_control autoware_simple_pure_pursuit autoware_core_localization autoware_ekf_localizer autoware_gyro_odometer autoware_localization_util autoware_ndt_scan_matcher autoware_pose_initializer autoware_stop_filter autoware_twist2accel autoware_core_map autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_loader autoware_map_projection_loader autoware_core_perception autoware_euclidean_cluster_object_detector autoware_ground_filter autoware_perception_objects_converter autoware_core_planning autoware_mission_planner autoware_objects_of_interest_marker_interface autoware_path_generator autoware_planning_factor_interface autoware_planning_topic_converter autoware_route_handler autoware_velocity_smoother autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_stop_line_module autoware_motion_velocity_obstacle_stop_module autoware_motion_velocity_planner autoware_motion_velocity_planner_common autoware_core_sensing autoware_crop_box_filter autoware_downsample_filters autoware_gnss_poser autoware_vehicle_velocity_converter autoware_planning_test_manager autoware_pyplot autoware_test_node autoware_test_utils autoware_testing autoware_core_vehicle

Package Summary

Tags No category tags.
Version 1.1.0
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Description
Checkout URI https://github.com/autowarefoundation/autoware_core.git
VCS Type git
VCS Version main
Last Updated 2025-06-07
Dev Status UNKNOWN
CI status No Continuous Integration
Released UNRELEASED
Tags planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

The autoware_motion_utils package

Additional Links

No additional links.

Maintainers

  • Satoshi Ota
  • Takayuki Murooka
  • Fumiya Watanabe
  • Kosuke Takeuchi
  • Taiki Tanaka
  • Takamasa Horibe
  • Tomoya Kimura
  • Mamoru Sobue

Authors

  • Takayuki Murooka
  • Satoshi Ota

Motion Utils package

Definition of terms

Segment

Segment in Autoware is the line segment between two successive points as follows.

segment

The nearest segment index and nearest point index to a certain position is not always th same. Therefore, we prepare two different utility functions to calculate a nearest index for points and segments.

In this section, the nearest index and nearest segment index search is explained.

We have the same functions for the nearest index search and nearest segment index search. Taking for the example the nearest index search, we have two types of functions.

The first function finds the nearest index with distance and yaw thresholds.

template <class T>
size_t findFirstNearestIndexWithSoftConstraints(
  const T & points, const geometry_msgs::msg::Pose & pose,
  const double dist_threshold = std::numeric_limits<double>::max(),
  const double yaw_threshold = std::numeric_limits<double>::max());

This function finds the first local solution within thresholds. The reason to find the first local one is to deal with some edge cases explained in the next subsection.

There are default parameters for thresholds arguments so that you can decide which thresholds to pass to the function.

  1. When both the distance and yaw thresholds are given.
    • First, try to find the nearest index with both the distance and yaw thresholds.
    • If not found, try to find again with only the distance threshold.
    • If not found, find without any thresholds.
  2. When only distance are given.
    • First, try to find the nearest index the distance threshold.
    • If not found, find without any thresholds.
  3. When no thresholds are given.
    • Find the nearest index.

The second function finds the nearest index in the lane whose id is lane_id.

size_t findNearestIndexFromLaneId(
  const autoware_internal_planning_msgs::msg::PathWithLaneId & path,
  const geometry_msgs::msg::Point & pos, const int64_t lane_id);

Application to various object

Many node packages often calculate the nearest index of objects. We will explain the recommended method to calculate it.

Nearest index for the ego

Assuming that the path length before the ego is short enough, we expect to find the correct nearest index in the following edge cases by findFirstNearestIndexWithSoftConstraints with both distance and yaw thresholds. Blue circles describes the distance threshold from the base link position and two blue lines describe the yaw threshold against the base link orientation. Among points in these cases, the correct nearest point which is red can be found.

ego_nearest_search

Therefore, the implementation is as follows.

const size_t ego_nearest_idx = findFirstNearestIndexWithSoftConstraints(points, ego_pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold);
const size_t ego_nearest_seg_idx = findFirstNearestIndexWithSoftConstraints(points, ego_pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold);

Nearest index for dynamic objects

For the ego nearest index, the orientation is considered in addition to the position since the ego is supposed to follow the points. However, for the dynamic objects (e.g., predicted object), sometimes its orientation may be different from the points order, e.g. the dynamic object driving backward although the ego is driving forward.

Therefore, the yaw threshold should not be considered for the dynamic object. The implementation is as follows.

const size_t dynamic_obj_nearest_idx = findFirstNearestIndexWithSoftConstraints(points, dynamic_obj_pose, dynamic_obj_nearest_dist_threshold);
const size_t dynamic_obj_nearest_seg_idx = findFirstNearestIndexWithSoftConstraints(points, dynamic_obj_pose, dynamic_obj_nearest_dist_threshold);

Nearest index for traffic objects

In lanelet maps, traffic objects belong to the specific lane. With this specific lane’s id, the correct nearest index can be found.

The implementation is as follows.

// first extract `lane_id` which the traffic object belong to.
const size_t traffic_obj_nearest_idx = findNearestIndexFromLaneId(path_with_lane_id, traffic_obj_pos, lane_id);
const size_t traffic_obj_nearest_seg_idx = findNearestSegmentIndexFromLaneId(path_with_lane_id, traffic_obj_pos, lane_id);

For developers

Some of the template functions in trajectory.hpp are mostly used for specific types (autoware_planning_msgs::msg::PathPoint, autoware_planning_msgs::msg::PathPoint, autoware_planning_msgs::msg::TrajectoryPoint), so they are exported as extern template functions to speed-up compilation time.

autoware_motion_utils.hpp header file was removed because the source files that directly/indirectly include this file took a long time for preprocessing.

CHANGELOG

Changelog for package autoware_motion_utils

1.1.0 (2025-05-01)

  • fix(autoware_path_optimizer): incorrect application of input velocity due to badly mapping output trajectory to input trajectory (#355)
    • changes to avoid improper mapping

    * Update common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>> ---------Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>

  • refactor(autoware_motion_utils): rewrite using modern C++ without API breakage (#348)
  • Contributors: Arjun Jagdish Ram, Yutaka Kondo

1.0.0 (2025-03-31)

0.3.0 (2025-03-21)

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Dependant Packages

Name Deps
autoware_trajectory
autoware_simple_pure_pursuit
autoware_pose_initializer
autoware_mission_planner
autoware_path_generator
autoware_planning_factor_interface
autoware_planning_topic_converter
autoware_velocity_smoother
autoware_behavior_velocity_planner
autoware_behavior_velocity_planner_common
autoware_behavior_velocity_stop_line_module
autoware_motion_velocity_obstacle_stop_module
autoware_motion_velocity_planner
autoware_motion_velocity_planner_common
autoware_planning_test_manager
tier4_debug_tools
driving_environment_analyzer
autoware_planning_data_analyzer
autoware_static_centerline_generator
planning_debug_tools
autoware_boundary_departure_checker
autoware_path_distance_calculator
autoware_autonomous_emergency_braking
autoware_collision_detector
autoware_control_performance_analysis
autoware_control_validator
autoware_lane_departure_checker
autoware_mpc_lateral_controller
autoware_operation_mode_transition_manager
autoware_pid_longitudinal_controller
autoware_predicted_path_checker
autoware_pure_pursuit
autoware_smart_mpc_trajectory_follower
autoware_trajectory_follower_base
autoware_trajectory_follower_node
autoware_vehicle_cmd_gate
autoware_control_evaluator
autoware_perception_online_evaluator
autoware_planning_evaluator
autoware_map_based_prediction
autoware_freespace_planner
autoware_mission_planner_universe
autoware_path_optimizer
autoware_path_smoother
autoware_remaining_distance_time_calculator
autoware_surround_obstacle_checker
autoware_behavior_path_avoidance_by_lane_change_module
autoware_behavior_path_dynamic_obstacle_avoidance_module
autoware_behavior_path_external_request_lane_change_module
autoware_behavior_path_goal_planner_module
autoware_behavior_path_lane_change_module
autoware_behavior_path_planner
autoware_behavior_path_planner_common
autoware_behavior_path_sampling_planner_module
autoware_behavior_path_side_shift_module
autoware_behavior_path_start_planner_module
autoware_behavior_path_static_obstacle_avoidance_module
autoware_behavior_velocity_blind_spot_module
autoware_behavior_velocity_crosswalk_module
autoware_behavior_velocity_detection_area_module
autoware_behavior_velocity_intersection_module
autoware_behavior_velocity_no_drivable_lane_module
autoware_behavior_velocity_no_stopping_area_module
autoware_behavior_velocity_occlusion_spot_module
autoware_behavior_velocity_rtc_interface
autoware_behavior_velocity_run_out_module
autoware_behavior_velocity_speed_bump_module
autoware_behavior_velocity_template_module
autoware_behavior_velocity_traffic_light_module
autoware_behavior_velocity_virtual_traffic_light_module
autoware_behavior_velocity_walkway_module
autoware_motion_velocity_dynamic_obstacle_stop_module
autoware_motion_velocity_obstacle_cruise_module
autoware_motion_velocity_obstacle_slow_down_module
autoware_motion_velocity_obstacle_velocity_limiter_module
autoware_motion_velocity_out_of_lane_module
autoware_motion_velocity_run_out_module
autoware_planning_validator
autoware_planning_validator_test_utils
autoware_planning_validator_trajectory_checker
autoware_path_sampler
autoware_simple_planning_simulator
autoware_default_adapi_universe
reaction_analyzer
autoware_accel_brake_map_calibrator
tier4_planning_factor_rviz_plugin
tier4_state_rviz_plugin

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_motion_utils at Robotics Stack Exchange

No version for distro noetic. Known supported distros are highlighted in the buttons above.
No version for distro galactic. Known supported distros are highlighted in the buttons above.
No version for distro iron. Known supported distros are highlighted in the buttons above.
No version for distro melodic. Known supported distros are highlighted in the buttons above.