Autoware.Auto
global_velocity_planner.hpp File Reference

This file defines the global_velocity_planner class. More...

#include <common/types.hpp>
#include <global_velocity_planner/visibility_control.hpp>
#include <motion_common/config.hpp>
#include <motion_common/motion_common.hpp>
#include <autoware_auto_mapping_msgs/srv/had_map_service.hpp>
#include <autoware_auto_planning_msgs/msg/had_map_route.hpp>
#include <autoware_auto_planning_msgs/msg/path.hpp>
#include <autoware_auto_planning_msgs/msg/path_point.hpp>
#include <autoware_auto_vehicle_msgs/msg/vehicle_kinematic_state.hpp>
#include <autoware_auto_vehicle_msgs/msg/vehicle_state_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/vehicle_state_report.hpp>
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <lanelet2_core/LaneletMap.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <cstdint>
#include <memory>
#include <string>
#include <vector>
Include dependency graph for global_velocity_planner.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  autoware::global_velocity_planner::point
 it is waypoint variable, any point should have speed limit (read from map), curvature which is calculated in calculate_curvatures function, and Trajectory point which is taken from lanelets in route. More...
 
struct  autoware::global_velocity_planner::GlobalVelocityPlannerConfig
 It is planner configuration parameters. More...
 
class  autoware::global_velocity_planner::GlobalVelocityPlanner
 

Namespaces

 autoware
 This file defines the lanelet2_map_provider_node class.
 
 autoware::global_velocity_planner
 TODO(berkay): Document namespaces!
 

Typedefs

using autoware::global_velocity_planner::State = autoware_auto_vehicle_msgs::msg::VehicleKinematicState
 

Functions

size_t GLOBAL_VELOCITY_PLANNER_PUBLIC autoware::global_velocity_planner::get_closest_lanelet (const lanelet::ConstLanelets &lanelets, const TrajectoryPoint &point)
 
float32_t GLOBAL_VELOCITY_PLANNER_PUBLIC autoware::global_velocity_planner::find_acceleration (const TrajectoryPoint &p1, const TrajectoryPoint &p2)
 
float32_t GLOBAL_VELOCITY_PLANNER_PUBLIC autoware::global_velocity_planner::find_velocity (const TrajectoryPoint &p1, const TrajectoryPoint &p2, float32_t longitudinal_acceleration)
 

Detailed Description

This file defines the global_velocity_planner class.