scenario_simulator_v2 C++ API
Public Member Functions | Public Attributes | Protected Member Functions | Friends | List of all members
concealer::FieldOperatorApplicationFor< AutowareUniverse > Class Reference

#include <field_operator_application_for_autoware_universe.hpp>

Inheritance diagram for concealer::FieldOperatorApplicationFor< AutowareUniverse >:
Inheritance graph
[legend]
Collaboration diagram for concealer::FieldOperatorApplicationFor< AutowareUniverse >:
Collaboration graph
[legend]

Public Member Functions

template<typename... Ts>
CONCEALER_PUBLIC FieldOperatorApplicationFor (Ts &&... xs)
 
 ~FieldOperatorApplicationFor () override
 
auto engage () -> void override
 
auto engageable () const -> bool override
 
auto engaged () const -> bool override
 
auto getAutowareStateName () const -> std::string override
 
auto getWaypoints () const -> traffic_simulator_msgs::msg::WaypointsArray override
 
auto getTurnIndicatorsCommand () const -> autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand override
 
auto getEmergencyStateName () const -> std::string override
 
auto getMinimumRiskManeuverBehaviorName () const -> std::string override
 
auto getMinimumRiskManeuverStateName () const -> std::string override
 
auto initialize (const geometry_msgs::msg::Pose &) -> void override
 
auto plan (const std::vector< geometry_msgs::msg::PoseStamped > &) -> void override
 
auto clearRoute () -> void override
 
auto requestAutoModeForCooperation (const std::string &, bool) -> void override
 
auto restrictTargetSpeed (double) const -> double override
 
auto sendCooperateCommand (const std::string &, const std::string &) -> void override
 
auto setVelocityLimit (double) -> void override
 
- Public Member Functions inherited from concealer::FieldOperatorApplication
CONCEALER_PUBLIC FieldOperatorApplication (const pid_t=0)
 
template<typename... Ts>
CONCEALER_PUBLIC FieldOperatorApplication (Ts &&... xs)
 
 ~FieldOperatorApplication () override=default
 
auto spinSome () -> void
 
auto initialized () const noexcept
 
virtual auto rethrow () const noexcept(false) -> void
 
- Public Member Functions inherited from concealer::TransitionAssertion< FieldOperatorApplicationFor< AutowareUniverse > >
 TransitionAssertion ()
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (Initializing)
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (WaitingForRoute)
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (Planning)
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (WaitingForEngage)
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (Driving)
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (ArrivedGoal)
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (Finalizing)
 

Public Attributes

SubscriberWrapper< autoware_auto_planning_msgs::msg::PathWithLaneId > getPathWithLaneId
 
- Public Attributes inherited from concealer::TransitionAssertion< FieldOperatorApplicationFor< AutowareUniverse > >
const std::chrono::steady_clock::time_point start
 
const std::chrono::seconds initialize_duration
 
bool have_never_been_engaged
 

Protected Member Functions

template<typename T >
auto getAutowareStateString (std::uint8_t state) const -> char const *
 
auto sendSIGINT () -> void override
 
- Protected Member Functions inherited from concealer::FieldOperatorApplication
auto stopRequest () noexcept -> void
 
auto isStopRequested () const noexcept -> bool
 
auto shutdownAutoware () -> void
 

Friends

struct TransitionAssertion< FieldOperatorApplicationFor< AutowareUniverse > >
 

Additional Inherited Members

- Protected Attributes inherited from concealer::FieldOperatorApplication
const pid_t process_id = 0
 
TaskQueue task_queue
 
bool initialize_was_called = false
 

Constructor & Destructor Documentation

◆ FieldOperatorApplicationFor()

template<typename... Ts>
CONCEALER_PUBLIC concealer::FieldOperatorApplicationFor< AutowareUniverse >::FieldOperatorApplicationFor ( Ts &&...  xs)
inlineexplicit

◆ ~FieldOperatorApplicationFor()

Member Function Documentation

◆ clearRoute()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::clearRoute ( ) -> void
overridevirtual

◆ engage()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::engage ( ) -> void
overridevirtual

◆ engageable()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::engageable ( ) const -> bool
overridevirtual

◆ engaged()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::engaged ( ) const -> bool
overridevirtual

◆ getAutowareStateName()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::getAutowareStateName ( ) const -> std::string
overridevirtual

◆ getAutowareStateString()

template<typename T >
auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::getAutowareStateString ( std::uint8_t  state) const -> char const *
inlineprotected

◆ getEmergencyStateName()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::getEmergencyStateName ( ) const -> std::string
overridevirtual

◆ getMinimumRiskManeuverBehaviorName()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::getMinimumRiskManeuverBehaviorName ( ) const -> std::string
overridevirtual

◆ getMinimumRiskManeuverStateName()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::getMinimumRiskManeuverStateName ( ) const -> std::string
overridevirtual

◆ getTurnIndicatorsCommand()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::getTurnIndicatorsCommand ( ) const -> autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand
overridevirtual

◆ getWaypoints()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::getWaypoints ( ) const -> traffic_simulator_msgs::msg::WaypointsArray
overridevirtual

◆ initialize()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::initialize ( const geometry_msgs::msg::Pose &  initial_pose) -> void
overridevirtual

◆ plan()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::plan ( const std::vector< geometry_msgs::msg::PoseStamped > &  route) -> void
overridevirtual

◆ requestAutoModeForCooperation()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::requestAutoModeForCooperation ( const std::string &  module_name,
bool  enable 
) -> void
overridevirtual

◆ restrictTargetSpeed()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::restrictTargetSpeed ( double  value) const -> double
overridevirtual

◆ sendCooperateCommand()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::sendCooperateCommand ( const std::string &  module_name,
const std::string &  command 
) -> void
overridevirtual

NOTE: Used cooperate statuses will be deleted correctly in Autoware side and provided via topic update. But, their update rate (typ. 10Hz) is lower than the one of scenario_simulator_v2. So, we need to check cooperate statuses if they are used or not in scenario_simulator_v2 side to avoid sending the same cooperate command when sending multiple commands between updates of cooperate statuses.

Implements concealer::FieldOperatorApplication.

◆ sendSIGINT()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::sendSIGINT ( ) -> void
overrideprotectedvirtual

◆ setVelocityLimit()

auto concealer::FieldOperatorApplicationFor< AutowareUniverse >::setVelocityLimit ( double  velocity_limit) -> void
overridevirtual

Friends And Related Function Documentation

◆ TransitionAssertion< FieldOperatorApplicationFor< AutowareUniverse > >

Member Data Documentation

◆ getPathWithLaneId

SubscriberWrapper<autoware_auto_planning_msgs::msg::PathWithLaneId> concealer::FieldOperatorApplicationFor< AutowareUniverse >::getPathWithLaneId

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