scenario_simulator_v2 C++ API
|
#include <field_operator_application.hpp>
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) |
~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 | getWaypoints () const -> traffic_simulator_msgs::msg::WaypointsArray |
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 |
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 |
using concealer::FieldOperatorApplication::AutoModeWithModule = tier4_rtc_msgs::srv::AutoModeWithModule |
using concealer::FieldOperatorApplication::AutowareState = autoware_system_msgs::msg::AutowareState |
using concealer::FieldOperatorApplication::ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode |
using concealer::FieldOperatorApplication::ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute |
using concealer::FieldOperatorApplication::Control = autoware_control_msgs::msg::Control |
using concealer::FieldOperatorApplication::CooperateCommands = tier4_rtc_msgs::srv::CooperateCommands |
using concealer::FieldOperatorApplication::CooperateStatusArray = tier4_rtc_msgs::msg::CooperateStatusArray |
using concealer::FieldOperatorApplication::Emergency = tier4_external_api_msgs::msg::Emergency |
using concealer::FieldOperatorApplication::Engage = tier4_external_api_msgs::srv::Engage |
using concealer::FieldOperatorApplication::InitializeLocalization = autoware_adapi_v1_msgs::srv::InitializeLocalization |
using concealer::FieldOperatorApplication::LocalizationInitializationState = autoware_adapi_v1_msgs::msg::LocalizationInitializationState |
using concealer::FieldOperatorApplication::MrmState = autoware_adapi_v1_msgs::msg::MrmState |
using concealer::FieldOperatorApplication::PathWithLaneId = tier4_planning_msgs::msg::PathWithLaneId |
using concealer::FieldOperatorApplication::SetRoutePoints = autoware_adapi_v1_msgs::srv::SetRoutePoints |
using concealer::FieldOperatorApplication::SetVelocityLimit = tier4_external_api_msgs::srv::SetVelocityLimit |
using concealer::FieldOperatorApplication::Trajectory = tier4_planning_msgs::msg::Trajectory |
using concealer::FieldOperatorApplication::TurnIndicatorsCommand = autoware_vehicle_msgs::msg::TurnIndicatorsCommand |
|
explicit |
concealer::FieldOperatorApplication::~FieldOperatorApplication | ( | ) |
auto concealer::FieldOperatorApplication::clearRoute | ( | ) | -> void |
auto concealer::FieldOperatorApplication::enableAutowareControl | ( | ) | -> void |
auto concealer::FieldOperatorApplication::engage | ( | ) | -> void |
auto concealer::FieldOperatorApplication::engageable | ( | ) | const -> bool |
auto concealer::FieldOperatorApplication::engaged | ( | ) | const -> bool |
auto concealer::FieldOperatorApplication::getWaypoints | ( | ) | const -> traffic_simulator_msgs::msg::WaypointsArray |
auto concealer::FieldOperatorApplication::initialize | ( | const geometry_msgs::msg::Pose & | initial_pose | ) | -> void |
auto concealer::FieldOperatorApplication::plan | ( | const std::vector< geometry_msgs::msg::PoseStamped > & | route | ) | -> void |
auto concealer::FieldOperatorApplication::requestAutoModeForCooperation | ( | const std::string & | module_name, |
bool | enable | ||
) | -> void |
|
inline |
auto concealer::FieldOperatorApplication::sendCooperateCommand | ( | const std::string & | module_name, |
const std::string & | command | ||
) | -> void |
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.
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
auto concealer::FieldOperatorApplication::setVelocityLimit | ( | double | velocity_limit | ) | -> void |
auto concealer::FieldOperatorApplication::spinSome | ( | ) | -> void |
std::string concealer::FieldOperatorApplication::autoware_state = "LAUNCHING" |
Subscriber<AutowareState> concealer::FieldOperatorApplication::getAutowareState |
Subscriber<Control> concealer::FieldOperatorApplication::getCommand |
Subscriber<CooperateStatusArray> concealer::FieldOperatorApplication::getCooperateStatusArray |
Subscriber<Emergency> concealer::FieldOperatorApplication::getEmergencyState |
Subscriber<MrmState> concealer::FieldOperatorApplication::getMrmState |
Subscriber<PathWithLaneId> concealer::FieldOperatorApplication::getPathWithLaneId |
Subscriber<Trajectory> concealer::FieldOperatorApplication::getTrajectory |
Subscriber<TurnIndicatorsCommand> concealer::FieldOperatorApplication::getTurnIndicatorsCommand |
bool concealer::FieldOperatorApplication::initialized = false |
bool concealer::FieldOperatorApplication::is_autoware_exited = false |
std::atomic<bool> concealer::FieldOperatorApplication::is_stop_requested = false |
std::string concealer::FieldOperatorApplication::minimum_risk_maneuver_behavior |
std::string concealer::FieldOperatorApplication::minimum_risk_maneuver_state |
const pid_t concealer::FieldOperatorApplication::process_id = 0 |
Service<ClearRoute> concealer::FieldOperatorApplication::requestClearRoute |
Service<CooperateCommands> concealer::FieldOperatorApplication::requestCooperateCommands |
Service<ChangeOperationMode> concealer::FieldOperatorApplication::requestEnableAutowareControl |
Service<InitializeLocalization> concealer::FieldOperatorApplication::requestInitialPose |
Service<SetRoutePoints> concealer::FieldOperatorApplication::requestSetRoutePoints |
Service<AutoModeWithModule> concealer::FieldOperatorApplication::requestSetRtcAutoMode |
Service<SetVelocityLimit> concealer::FieldOperatorApplication::requestSetVelocityLimit |
TaskQueue concealer::FieldOperatorApplication::task_queue |