scenario_simulator_v2 C++ API
Public Member Functions | Public Attributes | List of all members
traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner Class Reference

#include <longitudinal_speed_planning.hpp>

Public Member Functions

 LongitudinalSpeedPlanner (const double step_time, const std::string &entity)
 
auto getDynamicStates (double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &, const geometry_msgs::msg::Twist &current_twist, const geometry_msgs::msg::Accel &current_accel) const -> std::tuple< geometry_msgs::msg::Twist, geometry_msgs::msg::Accel, double >
 
auto getAccelerationDuration (double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &, const geometry_msgs::msg::Twist &current_twist, const geometry_msgs::msg::Accel &current_accel) const -> double
 
auto planConstraintsFromJerkAndTimeConstraint (double target_speed, const geometry_msgs::msg::Twist &current_twist, const geometry_msgs::msg::Accel &current_accel, double acceleration_duration, const traffic_simulator_msgs::msg::DynamicConstraints &constraints) -> traffic_simulator_msgs::msg::DynamicConstraints
 
auto getRunningDistance (double target_speed, const traffic_simulator_msgs::msg::DynamicConstraints &, const geometry_msgs::msg::Twist &current_twist, const geometry_msgs::msg::Accel &current_accel, double current_linear_jerk) const -> double
 
auto isAccelerating (double target_speed, const geometry_msgs::msg::Twist &current_twist) const -> bool
 
auto isDecelerating (double target_speed, const geometry_msgs::msg::Twist &current_twist) const -> bool
 
auto isTargetSpeedReached (double target_speed, const geometry_msgs::msg::Twist &current_twist, double tolerance=0.01) const noexcept -> bool
 

Public Attributes

const double step_time
 
const std::string entity
 

Constructor & Destructor Documentation

◆ LongitudinalSpeedPlanner()

traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner::LongitudinalSpeedPlanner ( const double  step_time,
const std::string &  entity 
)
explicit

Member Function Documentation

◆ getAccelerationDuration()

auto traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner::getAccelerationDuration ( double  target_speed,
const traffic_simulator_msgs::msg::DynamicConstraints &  constraints,
const geometry_msgs::msg::Twist &  current_twist,
const geometry_msgs::msg::Accel &  current_accel 
) const -> double

◆ getDynamicStates()

auto traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner::getDynamicStates ( double  target_speed,
const traffic_simulator_msgs::msg::DynamicConstraints &  constraints,
const geometry_msgs::msg::Twist &  current_twist,
const geometry_msgs::msg::Accel &  current_accel 
) const -> std::tuple<geometry_msgs::msg::Twist, geometry_msgs::msg::Accel, double>

◆ getRunningDistance()

auto traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner::getRunningDistance ( double  target_speed,
const traffic_simulator_msgs::msg::DynamicConstraints &  constraints,
const geometry_msgs::msg::Twist &  current_twist,
const geometry_msgs::msg::Accel &  current_accel,
double  current_linear_jerk 
) const -> double

A value of 0.01 is the allowable range for determination of target speed attainment. This value was determined heuristically rather than for technical reasons.

◆ isAccelerating()

auto traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner::isAccelerating ( double  target_speed,
const geometry_msgs::msg::Twist &  current_twist 
) const -> bool

◆ isDecelerating()

auto traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner::isDecelerating ( double  target_speed,
const geometry_msgs::msg::Twist &  current_twist 
) const -> bool

◆ isTargetSpeedReached()

auto traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner::isTargetSpeedReached ( double  target_speed,
const geometry_msgs::msg::Twist &  current_twist,
double  tolerance = 0.01 
) const -> bool
noexcept

◆ planConstraintsFromJerkAndTimeConstraint()

auto traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner::planConstraintsFromJerkAndTimeConstraint ( double  target_speed,
const geometry_msgs::msg::Twist &  current_twist,
const geometry_msgs::msg::Accel &  current_accel,
double  acceleration_duration,
const traffic_simulator_msgs::msg::DynamicConstraints &  constraints 
) -> traffic_simulator_msgs::msg::DynamicConstraints

Member Data Documentation

◆ entity

const std::string traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner::entity

◆ step_time

const double traffic_simulator::longitudinal_speed_planning::LongitudinalSpeedPlanner::step_time

The documentation for this class was generated from the following files: