scenario_simulator_v2 C++ API
Public Types | Public Member Functions | Public Attributes | List of all members
concealer::FieldOperatorApplication Struct Reference

#include <field_operator_application.hpp>

Inheritance diagram for concealer::FieldOperatorApplication:
Inheritance graph
[legend]
Collaboration diagram for concealer::FieldOperatorApplication:
Collaboration graph
[legend]

Public Types

using AutowareState = autoware_system_msgs::msg::AutowareState
 
using Control = autoware_control_msgs::msg::Control
 
using CooperateStatusArray = tier4_rtc_msgs::msg::CooperateStatusArray
 
using Emergency = tier4_external_api_msgs::msg::Emergency
 
using LocalizationInitializationState = autoware_adapi_v1_msgs::msg::LocalizationInitializationState
 
using MrmState = autoware_adapi_v1_msgs::msg::MrmState
 
using PathWithLaneId = tier4_planning_msgs::msg::PathWithLaneId
 
using Trajectory = tier4_planning_msgs::msg::Trajectory
 
using TurnIndicatorsCommand = autoware_vehicle_msgs::msg::TurnIndicatorsCommand
 
using ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute
 
using CooperateCommands = tier4_rtc_msgs::srv::CooperateCommands
 
using Engage = tier4_external_api_msgs::srv::Engage
 
using InitializeLocalization = autoware_adapi_v1_msgs::srv::InitializeLocalization
 
using SetRoutePoints = autoware_adapi_v1_msgs::srv::SetRoutePoints
 
using AutoModeWithModule = tier4_rtc_msgs::srv::AutoModeWithModule
 
using SetVelocityLimit = tier4_external_api_msgs::srv::SetVelocityLimit
 
using ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode
 

Public Member Functions

CONCEALER_PUBLIC FieldOperatorApplication (const pid_t=0)
 
template<typename... Ts>
CONCEALER_PUBLIC FieldOperatorApplication (Ts &&... xs)
 
 ~FieldOperatorApplication ()
 
auto spinSome () -> void
 
auto engage () -> void
 
auto engageable () const -> bool
 
auto engaged () const -> bool
 
auto initialize (const geometry_msgs::msg::Pose &) -> void
 
auto plan (const std::vector< geometry_msgs::msg::PoseStamped > &) -> void
 
auto clearRoute () -> void
 
auto getAutowareStateName () const
 
auto getMinimumRiskManeuverBehaviorName () const
 
auto getMinimumRiskManeuverStateName () const
 
auto getEmergencyStateName () const
 
auto getWaypoints () const -> traffic_simulator_msgs::msg::WaypointsArray
 
auto initialized () const noexcept
 
auto requestAutoModeForCooperation (const std::string &, bool) -> void
 
auto rethrow () const
 
auto sendCooperateCommand (const std::string &, const std::string &) -> void
 
auto setVelocityLimit (double) -> void
 
auto enableAutowareControl () -> void
 

Public Attributes

std::atomic< bool > is_stop_requested = false
 
bool is_autoware_exited = false
 
const pid_t process_id = 0
 
bool initialize_was_called = false
 
std::string autoware_state
 
tier4_rtc_msgs::msg::CooperateStatusArray latest_cooperate_status_array
 
std::string minimum_risk_maneuver_state
 
std::string minimum_risk_maneuver_behavior
 
SubscriberWrapper< AutowareStategetAutowareState
 
SubscriberWrapper< ControlgetCommand
 
SubscriberWrapper< CooperateStatusArraygetCooperateStatusArray
 
SubscriberWrapper< EmergencygetEmergencyState
 
SubscriberWrapper< MrmStategetMrmState
 
SubscriberWrapper< PathWithLaneIdgetPathWithLaneId
 
SubscriberWrapper< TrajectorygetTrajectory
 
SubscriberWrapper< TurnIndicatorsCommandgetTurnIndicatorsCommand
 
ServiceWithValidation< ClearRouterequestClearRoute
 
ServiceWithValidation< CooperateCommandsrequestCooperateCommands
 
ServiceWithValidation< EngagerequestEngage
 
ServiceWithValidation< InitializeLocalizationrequestInitialPose
 
ServiceWithValidation< SetRoutePointsrequestSetRoutePoints
 
ServiceWithValidation< AutoModeWithModulerequestSetRtcAutoMode
 
ServiceWithValidation< SetVelocityLimitrequestSetVelocityLimit
 
ServiceWithValidation< ChangeOperationModerequestEnableAutowareControl
 
TaskQueue task_queue
 

Additional Inherited Members

- Protected Member Functions inherited from concealer::TransitionAssertion< FieldOperatorApplication >
 TransitionAssertion ()
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (INITIALIZING)
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (WAITING_FOR_ROUTE)
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (PLANNING)
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (WAITING_FOR_ENGAGE)
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (DRIVING)
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (ARRIVED_GOAL)
 
 DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (FINALIZING)
 
- Protected Attributes inherited from concealer::TransitionAssertion< FieldOperatorApplication >
const std::chrono::steady_clock::time_point start
 
const std::chrono::seconds initialize_duration
 
bool have_never_been_engaged
 

Member Typedef Documentation

◆ AutoModeWithModule

using concealer::FieldOperatorApplication::AutoModeWithModule = tier4_rtc_msgs::srv::AutoModeWithModule

◆ AutowareState

using concealer::FieldOperatorApplication::AutowareState = autoware_system_msgs::msg::AutowareState

◆ ChangeOperationMode

using concealer::FieldOperatorApplication::ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode

◆ ClearRoute

using concealer::FieldOperatorApplication::ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute

◆ Control

using concealer::FieldOperatorApplication::Control = autoware_control_msgs::msg::Control

◆ CooperateCommands

using concealer::FieldOperatorApplication::CooperateCommands = tier4_rtc_msgs::srv::CooperateCommands

◆ CooperateStatusArray

using concealer::FieldOperatorApplication::CooperateStatusArray = tier4_rtc_msgs::msg::CooperateStatusArray

◆ Emergency

using concealer::FieldOperatorApplication::Emergency = tier4_external_api_msgs::msg::Emergency

◆ Engage

using concealer::FieldOperatorApplication::Engage = tier4_external_api_msgs::srv::Engage

◆ InitializeLocalization

using concealer::FieldOperatorApplication::InitializeLocalization = autoware_adapi_v1_msgs::srv::InitializeLocalization

◆ LocalizationInitializationState

using concealer::FieldOperatorApplication::LocalizationInitializationState = autoware_adapi_v1_msgs::msg::LocalizationInitializationState

◆ MrmState

using concealer::FieldOperatorApplication::MrmState = autoware_adapi_v1_msgs::msg::MrmState

◆ PathWithLaneId

using concealer::FieldOperatorApplication::PathWithLaneId = tier4_planning_msgs::msg::PathWithLaneId

◆ SetRoutePoints

using concealer::FieldOperatorApplication::SetRoutePoints = autoware_adapi_v1_msgs::srv::SetRoutePoints

◆ SetVelocityLimit

using concealer::FieldOperatorApplication::SetVelocityLimit = tier4_external_api_msgs::srv::SetVelocityLimit

◆ Trajectory

using concealer::FieldOperatorApplication::Trajectory = tier4_planning_msgs::msg::Trajectory

◆ TurnIndicatorsCommand

using concealer::FieldOperatorApplication::TurnIndicatorsCommand = autoware_vehicle_msgs::msg::TurnIndicatorsCommand

Constructor & Destructor Documentation

◆ FieldOperatorApplication() [1/2]

concealer::FieldOperatorApplication::FieldOperatorApplication ( const pid_t  pid = 0)
explicit

◆ FieldOperatorApplication() [2/2]

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

◆ ~FieldOperatorApplication()

concealer::FieldOperatorApplication::~FieldOperatorApplication ( )

Member Function Documentation

◆ clearRoute()

auto concealer::FieldOperatorApplication::clearRoute ( ) -> void

◆ enableAutowareControl()

auto concealer::FieldOperatorApplication::enableAutowareControl ( ) -> void

◆ engage()

auto concealer::FieldOperatorApplication::engage ( ) -> void

◆ engageable()

auto concealer::FieldOperatorApplication::engageable ( ) const -> bool

◆ engaged()

auto concealer::FieldOperatorApplication::engaged ( ) const -> bool

◆ getAutowareStateName()

auto concealer::FieldOperatorApplication::getAutowareStateName ( ) const
inline

◆ getEmergencyStateName()

auto concealer::FieldOperatorApplication::getEmergencyStateName ( ) const
inline

◆ getMinimumRiskManeuverBehaviorName()

auto concealer::FieldOperatorApplication::getMinimumRiskManeuverBehaviorName ( ) const
inline

◆ getMinimumRiskManeuverStateName()

auto concealer::FieldOperatorApplication::getMinimumRiskManeuverStateName ( ) const
inline

◆ getWaypoints()

auto concealer::FieldOperatorApplication::getWaypoints ( ) const -> traffic_simulator_msgs::msg::WaypointsArray

◆ initialize()

auto concealer::FieldOperatorApplication::initialize ( const geometry_msgs::msg::Pose &  initial_pose) -> void

◆ initialized()

auto concealer::FieldOperatorApplication::initialized ( ) const
inlinenoexcept

◆ plan()

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

◆ requestAutoModeForCooperation()

auto concealer::FieldOperatorApplication::requestAutoModeForCooperation ( const std::string &  module_name,
bool  enable 
) -> void

◆ rethrow()

auto concealer::FieldOperatorApplication::rethrow ( ) const
inline

◆ sendCooperateCommand()

auto concealer::FieldOperatorApplication::sendCooperateCommand ( const std::string &  module_name,
const std::string &  command 
) -> void

◆ setVelocityLimit()

auto concealer::FieldOperatorApplication::setVelocityLimit ( double  velocity_limit) -> void

◆ spinSome()

auto concealer::FieldOperatorApplication::spinSome ( ) -> void

Member Data Documentation

◆ autoware_state

std::string concealer::FieldOperatorApplication::autoware_state

◆ getAutowareState

SubscriberWrapper<AutowareState> concealer::FieldOperatorApplication::getAutowareState

◆ getCommand

SubscriberWrapper<Control> concealer::FieldOperatorApplication::getCommand

◆ getCooperateStatusArray

SubscriberWrapper<CooperateStatusArray> concealer::FieldOperatorApplication::getCooperateStatusArray

◆ getEmergencyState

SubscriberWrapper<Emergency> concealer::FieldOperatorApplication::getEmergencyState

◆ getMrmState

SubscriberWrapper<MrmState> concealer::FieldOperatorApplication::getMrmState

◆ getPathWithLaneId

SubscriberWrapper<PathWithLaneId> concealer::FieldOperatorApplication::getPathWithLaneId

◆ getTrajectory

SubscriberWrapper<Trajectory> concealer::FieldOperatorApplication::getTrajectory

◆ getTurnIndicatorsCommand

SubscriberWrapper<TurnIndicatorsCommand> concealer::FieldOperatorApplication::getTurnIndicatorsCommand

◆ initialize_was_called

bool concealer::FieldOperatorApplication::initialize_was_called = false

◆ is_autoware_exited

bool concealer::FieldOperatorApplication::is_autoware_exited = false

◆ is_stop_requested

std::atomic<bool> concealer::FieldOperatorApplication::is_stop_requested = false

◆ latest_cooperate_status_array

tier4_rtc_msgs::msg::CooperateStatusArray concealer::FieldOperatorApplication::latest_cooperate_status_array

◆ minimum_risk_maneuver_behavior

std::string concealer::FieldOperatorApplication::minimum_risk_maneuver_behavior

◆ minimum_risk_maneuver_state

std::string concealer::FieldOperatorApplication::minimum_risk_maneuver_state

◆ process_id

const pid_t concealer::FieldOperatorApplication::process_id = 0

◆ requestClearRoute

ServiceWithValidation<ClearRoute> concealer::FieldOperatorApplication::requestClearRoute

◆ requestCooperateCommands

ServiceWithValidation<CooperateCommands> concealer::FieldOperatorApplication::requestCooperateCommands

◆ requestEnableAutowareControl

ServiceWithValidation<ChangeOperationMode> concealer::FieldOperatorApplication::requestEnableAutowareControl

◆ requestEngage

ServiceWithValidation<Engage> concealer::FieldOperatorApplication::requestEngage

◆ requestInitialPose

ServiceWithValidation<InitializeLocalization> concealer::FieldOperatorApplication::requestInitialPose

◆ requestSetRoutePoints

ServiceWithValidation<SetRoutePoints> concealer::FieldOperatorApplication::requestSetRoutePoints

◆ requestSetRtcAutoMode

ServiceWithValidation<AutoModeWithModule> concealer::FieldOperatorApplication::requestSetRtcAutoMode

◆ requestSetVelocityLimit

ServiceWithValidation<SetVelocityLimit> concealer::FieldOperatorApplication::requestSetVelocityLimit

◆ task_queue

TaskQueue concealer::FieldOperatorApplication::task_queue

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