scenario_simulator_v2 C++ API
Classes | Enumerations | Functions | Variables
concealer Namespace Reference

Classes

class  Autoware
 
class  AutowareUniverse
 
class  ContinuousTransformBroadcaster
 
class  FieldOperatorApplicationFor
 
class  FieldOperatorApplication
 
class  FieldOperatorApplicationFor< AutowareUniverse >
 
struct  has_data_member_allow_goal_modification
 
struct  has_data_member_allow_goal_modification< T, std::void_t< decltype(std::declval< T >().allow_goal_modification)> >
 
struct  has_data_member_option
 
struct  has_data_member_option< T, std::void_t< decltype(std::declval< T >().option)> >
 
class  PublisherWrapper
 
class  ServiceWithValidation
 
class  SubscriberWrapper
 
class  TaskQueue
 
struct  TransitionAssertion
 
struct  lister
 
struct  HasStaticNONE
 
struct  HasStaticNONE< T, std::void_t< decltype(T::NONE)> >
 
struct  HasStaticLANE_CHANGE_LEFT
 
struct  HasStaticLANE_CHANGE_LEFT< T, std::void_t< decltype(T::LANE_CHANGE_LEFT)> >
 
struct  HasStaticLANE_CHANGE_RIGHT
 
struct  HasStaticLANE_CHANGE_RIGHT< T, std::void_t< decltype(T::LANE_CHANGE_RIGHT)> >
 
struct  HasStaticAVOIDANCE_LEFT
 
struct  HasStaticAVOIDANCE_LEFT< T, std::void_t< decltype(T::AVOIDANCE_LEFT)> >
 
struct  HasStaticAVOIDANCE_RIGHT
 
struct  HasStaticAVOIDANCE_RIGHT< T, std::void_t< decltype(T::AVOIDANCE_RIGHT)> >
 
struct  HasStaticGOAL_PLANNER
 
struct  HasStaticGOAL_PLANNER< T, std::void_t< decltype(T::GOAL_PLANNER)> >
 
struct  HasStaticSTART_PLANNER
 
struct  HasStaticSTART_PLANNER< T, std::void_t< decltype(T::START_PLANNER)> >
 
struct  HasStaticPULL_OUT
 
struct  HasStaticPULL_OUT< T, std::void_t< decltype(T::PULL_OUT)> >
 
struct  HasStaticTRAFFIC_LIGHT
 
struct  HasStaticTRAFFIC_LIGHT< T, std::void_t< decltype(T::TRAFFIC_LIGHT)> >
 
struct  HasStaticINTERSECTION
 
struct  HasStaticINTERSECTION< T, std::void_t< decltype(T::INTERSECTION)> >
 
struct  HasStaticINTERSECTION_OCCLUSION
 
struct  HasStaticINTERSECTION_OCCLUSION< T, std::void_t< decltype(T::INTERSECTION_OCCLUSION)> >
 
struct  HasStaticCROSSWALK
 
struct  HasStaticCROSSWALK< T, std::void_t< decltype(T::CROSSWALK)> >
 
struct  HasStaticBLIND_SPOT
 
struct  HasStaticBLIND_SPOT< T, std::void_t< decltype(T::BLIND_SPOT)> >
 
struct  HasStaticDETECTION_AREA
 
struct  HasStaticDETECTION_AREA< T, std::void_t< decltype(T::DETECTION_AREA)> >
 
struct  HasStaticNO_STOPPING_AREA
 
struct  HasStaticNO_STOPPING_AREA< T, std::void_t< decltype(T::NO_STOPPING_AREA)> >
 
struct  HasStaticOCCLUSION_SPOT
 
struct  HasStaticOCCLUSION_SPOT< T, std::void_t< decltype(T::OCCLUSION_SPOT)> >
 
struct  HasStaticEXT_REQUEST_LANE_CHANGE_LEFT
 
struct  HasStaticEXT_REQUEST_LANE_CHANGE_LEFT< T, std::void_t< decltype(T::EXT_REQUEST_LANE_CHANGE_LEFT)> >
 
struct  HasStaticEXT_REQUEST_LANE_CHANGE_RIGHT
 
struct  HasStaticEXT_REQUEST_LANE_CHANGE_RIGHT< T, std::void_t< decltype(T::EXT_REQUEST_LANE_CHANGE_RIGHT)> >
 
struct  HasStaticAVOIDANCE_BY_LC_LEFT
 
struct  HasStaticAVOIDANCE_BY_LC_LEFT< T, std::void_t< decltype(T::AVOIDANCE_BY_LC_LEFT)> >
 
struct  HasStaticAVOIDANCE_BY_LC_RIGHT
 
struct  HasStaticAVOIDANCE_BY_LC_RIGHT< T, std::void_t< decltype(T::AVOIDANCE_BY_LC_RIGHT)> >
 
struct  HasStaticNO_DRIVABLE_LANE
 
struct  HasStaticNO_DRIVABLE_LANE< T, std::void_t< decltype(T::NO_DRIVABLE_LANE)> >
 
struct  HasStaticCOMFORTABLE_STOP
 
struct  HasStaticCOMFORTABLE_STOP< T, std::void_t< decltype(T::COMFORTABLE_STOP)> >
 
struct  HasStaticEMERGENCY_STOP
 
struct  HasStaticEMERGENCY_STOP< T, std::void_t< decltype(T::EMERGENCY_STOP)> >
 
struct  HasStaticUNKNOWN
 
struct  HasStaticUNKNOWN< T, std::void_t< decltype(T::UNKNOWN)> >
 
struct  HasStaticPULL_OVER
 
struct  HasStaticPULL_OVER< T, std::void_t< decltype(T::PULL_OVER)> >
 
struct  HasDistance
 
struct  HasDistance< T, std::void_t< decltype(std::declval< T >().distance)> >
 

Enumerations

enum class  ThreadSafety : bool { unsafe , safe }
 

Functions

auto execute (const std::vector< std::string > &) -> int
 
auto dollar (const std::string &command) -> std::string
 
void sudokill (const pid_t process_id)
 
auto isPackageExists (const std::string &package_name) noexcept -> bool
 
template<typename Parameters >
auto ros2_launch (const std::string &package, const std::string &file, const Parameters &parameters)
 
template<auto N, typename Tuples >
auto operator<< (std::ostream &ostream, const lister< N, Tuples > &lister) -> std::ostream &
 
template<auto N, typename Tuples >
auto listup (const Tuples &tuples) -> lister< N, Tuples >
 
template<typename T >
auto toModuleType (const std::string &module_name)
 
template<typename CooperateStatusType >
bool isValidCooperateStatus (const CooperateStatusType &cooperate_status, std::uint8_t command_type, std::uint8_t module_type)
 
template<typename T >
auto toMinimumRiskManeuverBehaviorString (const std::uint8_t &behavior_number) -> std::string
 
auto toMinimumRiskManeuverStateString (const std::uint8_t &state_number) -> std::string
 

Variables

template<typename... Ts>
constexpr auto has_data_member_allow_goal_modification_v
 
template<typename... Ts>
constexpr auto has_data_member_option_v = has_data_member_option<Ts...>::value
 

Detailed Description

Todo:
: pzyskowski : use conditional variables to wait for new messages instead of sleep_for

Enumeration Type Documentation

◆ ThreadSafety

enum concealer::ThreadSafety : bool
strong
Enumerator
unsafe 
safe 

Function Documentation

◆ dollar()

auto concealer::dollar ( const std::string &  command) -> std::string

◆ execute()

auto concealer::execute ( const std::vector< std::string > &  f_xs) -> int

◆ isPackageExists()

auto concealer::isPackageExists ( const std::string &  package_name) -> bool
noexcept

◆ isValidCooperateStatus()

template<typename CooperateStatusType >
bool concealer::isValidCooperateStatus ( const CooperateStatusType &  cooperate_status,
std::uint8_t  command_type,
std::uint8_t  module_type 
)

NOTE1: the finish_distance filter is set to over -20.0, because some valid rtc statuses has negative finish_distance due to the errors of localization or numerical calculation. This threshold is advised by a member of TIER IV planning and control team.

NOTE2: The difference in the variable referred as a distance is the impact of the message specification changes in the following URL. This was also decided after consulting with a member of TIER IV planning and control team. ref: https://github.com/tier4/tier4_autoware_msgs/commit/8b85e6e43aa48cf4a439c77bf4bf6aee2e70c3ef

◆ listup()

template<auto N, typename Tuples >
auto concealer::listup ( const Tuples &  tuples) -> lister<N, Tuples>

◆ operator<<()

template<auto N, typename Tuples >
auto concealer::operator<< ( std::ostream &  ostream,
const lister< N, Tuples > &  lister 
) -> std::ostream &

◆ ros2_launch()

template<typename Parameters >
auto concealer::ros2_launch ( const std::string &  package,
const std::string &  file,
const Parameters &  parameters 
)

◆ sudokill()

void concealer::sudokill ( const pid_t  process_id)

◆ toMinimumRiskManeuverBehaviorString()

template<typename T >
auto concealer::toMinimumRiskManeuverBehaviorString ( const std::uint8_t &  behavior_number) -> std::string

◆ toMinimumRiskManeuverStateString()

auto concealer::toMinimumRiskManeuverStateString ( const std::uint8_t &  state_number) -> std::string

◆ toModuleType()

template<typename T >
auto concealer::toModuleType ( const std::string &  module_name)

Variable Documentation

◆ has_data_member_allow_goal_modification_v

template<typename... Ts>
constexpr auto concealer::has_data_member_allow_goal_modification_v
inlineconstexpr
Initial value:
=
has_data_member_allow_goal_modification<Ts...>::value

◆ has_data_member_option_v

template<typename... Ts>
constexpr auto concealer::has_data_member_option_v = has_data_member_option<Ts...>::value
inlineconstexpr