scenario_simulator_v2 C++ API
|
#include <autoware_universe.hpp>
Public Types | |
using | AccelWithCovarianceStamped = geometry_msgs::msg::AccelWithCovarianceStamped |
using | Control = autoware_control_msgs::msg::Control |
using | ControlModeCommand = autoware_vehicle_msgs::srv::ControlModeCommand |
using | ControlModeReport = autoware_vehicle_msgs::msg::ControlModeReport |
using | GearCommand = autoware_vehicle_msgs::msg::GearCommand |
using | GearReport = autoware_vehicle_msgs::msg::GearReport |
using | Odometry = nav_msgs::msg::Odometry |
using | PathWithLaneId = tier4_planning_msgs::msg::PathWithLaneId |
using | PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped |
using | SteeringReport = autoware_vehicle_msgs::msg::SteeringReport |
using | TurnIndicatorsCommand = autoware_vehicle_msgs::msg::TurnIndicatorsCommand |
using | TurnIndicatorsReport = autoware_vehicle_msgs::msg::TurnIndicatorsReport |
using | VelocityReport = autoware_vehicle_msgs::msg::VelocityReport |
Public Member Functions | |
CONCEALER_PUBLIC | AutowareUniverse (bool) |
~AutowareUniverse () | |
auto | rethrow () -> void |
auto | updateLocalization () -> void |
auto | updateVehicleState () -> void |
auto | getVehicleCommand () const -> std::tuple< double, double, double, double, int > |
auto | getRouteLanelets () const -> std::vector< std::int64_t > |
auto | getControlModeReport () const -> ControlModeReport |
auto | setManualMode () -> void |
Public Member Functions inherited from concealer::ContinuousTransformBroadcaster< AutowareUniverse > | |
const auto & | setTransform (const geometry_msgs::msg::Pose &pose) |
ContinuousTransformBroadcaster () | |
Public Attributes | |
SubscriberWrapper< Control > | getCommand |
SubscriberWrapper< GearCommand > | getGearCommand |
SubscriberWrapper< TurnIndicatorsCommand > | getTurnIndicatorsCommand |
SubscriberWrapper< PathWithLaneId > | getPathWithLaneId |
PublisherWrapper< AccelWithCovarianceStamped > | setAcceleration |
PublisherWrapper< Odometry > | setOdometry |
PublisherWrapper< PoseWithCovarianceStamped > | setPose |
PublisherWrapper< SteeringReport > | setSteeringReport |
PublisherWrapper< GearReport > | setGearReport |
PublisherWrapper< ControlModeReport > | setControlModeReport |
PublisherWrapper< VelocityReport > | setVelocityReport |
PublisherWrapper< TurnIndicatorsReport > | setTurnIndicatorsReport |
std::atomic< geometry_msgs::msg::Accel > | current_acceleration |
std::atomic< geometry_msgs::msg::Pose > | current_pose |
std::atomic< geometry_msgs::msg::Twist > | current_twist |
using concealer::AutowareUniverse::AccelWithCovarianceStamped = geometry_msgs::msg::AccelWithCovarianceStamped |
using concealer::AutowareUniverse::Control = autoware_control_msgs::msg::Control |
using concealer::AutowareUniverse::ControlModeCommand = autoware_vehicle_msgs::srv::ControlModeCommand |
using concealer::AutowareUniverse::ControlModeReport = autoware_vehicle_msgs::msg::ControlModeReport |
using concealer::AutowareUniverse::GearCommand = autoware_vehicle_msgs::msg::GearCommand |
using concealer::AutowareUniverse::GearReport = autoware_vehicle_msgs::msg::GearReport |
using concealer::AutowareUniverse::Odometry = nav_msgs::msg::Odometry |
using concealer::AutowareUniverse::PathWithLaneId = tier4_planning_msgs::msg::PathWithLaneId |
using concealer::AutowareUniverse::PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped |
using concealer::AutowareUniverse::SteeringReport = autoware_vehicle_msgs::msg::SteeringReport |
using concealer::AutowareUniverse::TurnIndicatorsCommand = autoware_vehicle_msgs::msg::TurnIndicatorsCommand |
using concealer::AutowareUniverse::TurnIndicatorsReport = autoware_vehicle_msgs::msg::TurnIndicatorsReport |
using concealer::AutowareUniverse::VelocityReport = autoware_vehicle_msgs::msg::VelocityReport |
|
explicit |
concealer::AutowareUniverse::~AutowareUniverse | ( | ) |
auto concealer::AutowareUniverse::getControlModeReport | ( | ) | const -> ControlModeReport |
auto concealer::AutowareUniverse::getRouteLanelets | ( | ) | const -> std::vector<std::int64_t> |
auto concealer::AutowareUniverse::getVehicleCommand | ( | ) | const -> std::tuple<double, double, double, double, int> |
auto concealer::AutowareUniverse::rethrow | ( | ) | -> void |
auto concealer::AutowareUniverse::setManualMode | ( | ) | -> void |
auto concealer::AutowareUniverse::updateLocalization | ( | ) | -> void |
auto concealer::AutowareUniverse::updateVehicleState | ( | ) | -> void |
std::atomic<geometry_msgs::msg::Accel> concealer::AutowareUniverse::current_acceleration |
std::atomic<geometry_msgs::msg::Pose> concealer::AutowareUniverse::current_pose |
std::atomic<geometry_msgs::msg::Twist> concealer::AutowareUniverse::current_twist |
SubscriberWrapper<Control> concealer::AutowareUniverse::getCommand |
SubscriberWrapper<GearCommand> concealer::AutowareUniverse::getGearCommand |
SubscriberWrapper<PathWithLaneId> concealer::AutowareUniverse::getPathWithLaneId |
SubscriberWrapper<TurnIndicatorsCommand> concealer::AutowareUniverse::getTurnIndicatorsCommand |
PublisherWrapper<AccelWithCovarianceStamped> concealer::AutowareUniverse::setAcceleration |
PublisherWrapper<ControlModeReport> concealer::AutowareUniverse::setControlModeReport |
PublisherWrapper<GearReport> concealer::AutowareUniverse::setGearReport |
PublisherWrapper<Odometry> concealer::AutowareUniverse::setOdometry |
PublisherWrapper<PoseWithCovarianceStamped> concealer::AutowareUniverse::setPose |
PublisherWrapper<SteeringReport> concealer::AutowareUniverse::setSteeringReport |
PublisherWrapper<TurnIndicatorsReport> concealer::AutowareUniverse::setTurnIndicatorsReport |
PublisherWrapper<VelocityReport> concealer::AutowareUniverse::setVelocityReport |