Go to the documentation of this file.
19 #ifndef BEHAVIOR_PLANNER__TRAJECTORY_MANAGER_HPP_
20 #define BEHAVIOR_PLANNER__TRAJECTORY_MANAGER_HPP_
25 #include <autoware_auto_planning_msgs/msg/had_map_route.hpp>
26 #include <autoware_auto_planning_msgs/msg/trajectory.hpp>
27 #include <autoware_auto_vehicle_msgs/msg/vehicle_kinematic_state.hpp>
65 void clear_trajectory();
66 void set_trajectory(
const Trajectory & trajectory);
68 size_t get_remaining_length(
const State & state);
73 void set_sub_trajectories();
74 std::size_t get_closest_state(
const State & state,
const Trajectory & trajectory);
76 void set_time_from_start(
Trajectory * trajectory);
81 std::vector<Trajectory> m_sub_trajectories;
82 size_t m_selected_trajectory;
88 #endif // BEHAVIOR_PLANNER__TRAJECTORY_MANAGER_HPP_
float32_t subroute_goal_offset_lane2parking
Definition: trajectory_manager.hpp:50
autoware_auto_planning_msgs::msg::TrajectoryPoint TrajectoryPoint
Definition: motion_testing_publisher.hpp:36
This file includes common type definition.
Definition: behavior_planner.launch.py:1
float32_t cg_to_vehicle_center
Definition: trajectory_manager.hpp:52
float32_t subroute_goal_offset_parking2lane
Definition: trajectory_manager.hpp:51
float32_t heading_weight
Definition: trajectory_manager.hpp:49
Class that splits trajectory at gear changing points and publish them separately.
Definition: trajectory_manager.hpp:60
bool bool8_t
Definition: types.hpp:39
float32_t goal_distance_thresh
Definition: trajectory_manager.hpp:47
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Definition: trajectory_manager.hpp:45
float float32_t
Definition: types.hpp:45
autoware_auto_planning_msgs::msg::Trajectory Trajectory
Definition: motion_common.hpp:41
autoware_auto_vehicle_msgs::msg::VehicleKinematicState State
Definition: behavior_planner.hpp:57
autoware_auto_vehicle_msgs::msg::VehicleKinematicState VehicleKinematicState
Definition: trajectory_spoofer.hpp:42
float32_t stop_velocity_thresh
Definition: trajectory_manager.hpp:48