Autoware.Auto
|
|
Implementation of interface for LGSVL simulator. More...
#include <lgsvl_interface/visibility_control.hpp>
#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/gear_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/gear_report.hpp>
#include <autoware_auto_vehicle_msgs/msg/hand_brake_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/hand_brake_report.hpp>
#include <autoware_auto_vehicle_msgs/msg/headlights_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/horn_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/wipers_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/hazard_lights_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/raw_control_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/vehicle_kinematic_state.hpp>
#include <autoware_auto_vehicle_msgs/msg/vehicle_state_command.hpp>
#include <autoware_auto_vehicle_msgs/msg/vehicle_state_report.hpp>
#include <autoware_auto_vehicle_msgs/srv/autonomy_mode_change.hpp>
#include <lgsvl_msgs/msg/vehicle_odometry.hpp>
#include <lgsvl_msgs/msg/can_bus_data.hpp>
#include <lgsvl_msgs/msg/vehicle_control_data.hpp>
#include <lgsvl_msgs/msg/vehicle_state_data.hpp>
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <tf2_msgs/msg/tf_message.hpp>
#include <geometry/lookup_table.hpp>
#include <rclcpp/rclcpp.hpp>
#include <vehicle_interface/platform_interface.hpp>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.h>
#include <chrono>
#include <memory>
#include <string>
#include <unordered_map>
#include <utility>
Go to the source code of this file.
Classes | |
class | lgsvl_interface::LgsvlInterface |
Namespaces | |
lgsvl_interface | |
Typedefs | |
using | lgsvl_interface::Table1D = ::autoware::common::helper_functions::LookupTable1D< double > |
using | lgsvl_interface::VSC = autoware_auto_vehicle_msgs::msg::VehicleStateCommand |
using | lgsvl_interface::VSD = lgsvl_msgs::msg::VehicleStateData |
using | lgsvl_interface::WIPER_TYPE = decltype(VSC::wiper) |
using | lgsvl_interface::GEAR_TYPE = std::remove_const< decltype(autoware_auto_vehicle_msgs::msg::GearReport::DRIVE_1)>::type |
using | lgsvl_interface::MODE_TYPE = decltype(VSC::mode) |
Variables | |
constexpr static double | lgsvl_interface::COV_X_VAR = 0.1 |
constexpr static double | lgsvl_interface::COV_Y_VAR = 0.1 |
constexpr static double | lgsvl_interface::COV_Z_VAR = 0.1 |
constexpr static double | lgsvl_interface::COV_RX_VAR = 0.1 |
constexpr static double | lgsvl_interface::COV_RY_VAR = 0.1 |
constexpr static double | lgsvl_interface::COV_RZ_VAR = 0.1 |
constexpr static int32_t | lgsvl_interface::COV_X = 0 |
constexpr static int32_t | lgsvl_interface::COV_Y = 7 |
constexpr static int32_t | lgsvl_interface::COV_Z = 14 |
constexpr static int32_t | lgsvl_interface::COV_RX = 21 |
constexpr static int32_t | lgsvl_interface::COV_RY = 28 |
constexpr static int32_t | lgsvl_interface::COV_RZ = 35 |
constexpr bool | lgsvl_interface::PUBLISH = true |
constexpr bool | lgsvl_interface::NO_PUBLISH = false |
Implementation of interface for LGSVL simulator.