scenario_simulator_v2 C++ API
|
Classes | |
class | StopWatch |
Enumerations | |
enum class | LidarType { VLP16 , VLP32 } |
Functions | |
traffic_simulator_msgs::msg::ActionStatus | constructActionStatus (double linear_vel=0, double angular_vel=0, double linear_accel=0, double angular_accel=0) |
helper function for constructing action status More... | |
LaneletPose | constructLaneletPose (lanelet::Id lanelet_id, double s, double offset=0, double roll=0, double pitch=0, double yaw=0) |
helper function for constructing lanelet pose More... | |
auto | constructCanonicalizedLaneletPose (lanelet::Id lanelet_id, double s, double offset, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> CanonicalizedLaneletPose |
helper function for constructing canonicalized lanelet pose More... | |
auto | constructCanonicalizedLaneletPose (lanelet::Id lanelet_id, double s, double offset, double roll, double pitch, double yaw, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> CanonicalizedLaneletPose |
helper function for constructing canonicalized lanelet pose More... | |
geometry_msgs::msg::Vector3 | constructRPY (double roll=0, double pitch=0, double yaw=0) |
helper function for constructing rpy More... | |
geometry_msgs::msg::Vector3 | constructRPYfromQuaternion (geometry_msgs::msg::Quaternion quaternion) |
helper function for constructing rpy More... | |
geometry_msgs::msg::Pose | constructPose (double x, double y, double z, double roll, double pitch, double yaw) |
helper function for constructing pose More... | |
template<typename T > | |
std::vector< T > | getUniqueValues (const std::vector< T > &input_vector) |
helper function for creating vector without duplicates, with preserved order More... | |
const simulation_api_schema::LidarConfiguration | constructLidarConfiguration (const LidarType type, const std::string &entity, const std::string &architecture_type, const double lidar_sensor_delay=0, const double horizontal_resolution=1.0/180.0 *M_PI) |
const simulation_api_schema::DetectionSensorConfiguration | constructDetectionSensorConfiguration (const std::string &entity, const std::string &architecture_type, const double update_duration, const double range=300.0, const bool detect_all_objects_in_range=false, const double pos_noise_stddev=0, const int random_seed=0, const double probability_of_lost=0, const double object_recognition_delay=0, const double object_recognition_ground_truth_delay=0) |
|
strong |
traffic_simulator_msgs::msg::ActionStatus traffic_simulator::helper::constructActionStatus | ( | double | linear_vel = 0 , |
double | angular_vel = 0 , |
||
double | linear_accel = 0 , |
||
double | angular_accel = 0 |
||
) |
helper function for constructing action status
linear_vel | linear velocity |
angular_vel | angular velocity |
linear_accel | linear acceleration |
angular_accel | angular acceleration |
auto traffic_simulator::helper::constructCanonicalizedLaneletPose | ( | lanelet::Id | lanelet_id, |
double | s, | ||
double | offset, | ||
const std::shared_ptr< hdmap_utils::HdMapUtils > & | hdmap_utils_ptr | ||
) | -> CanonicalizedLaneletPose |
helper function for constructing canonicalized lanelet pose
lanelet_id | lanelet id |
s | s value in lane coordinate |
offset | offset value in lane coordinate |
hdmap_utils_ptr | pointer to HdmapUtils |
auto traffic_simulator::helper::constructCanonicalizedLaneletPose | ( | lanelet::Id | lanelet_id, |
double | s, | ||
double | offset, | ||
double | roll, | ||
double | pitch, | ||
double | yaw, | ||
const std::shared_ptr< hdmap_utils::HdMapUtils > & | hdmap_utils_ptr | ||
) | -> CanonicalizedLaneletPose |
helper function for constructing canonicalized lanelet pose
lanelet_id | lanelet id |
s | s value in lane coordinate |
offset | offset value in lane coordinate |
roll | roll value in the lane coordinate |
pitch | pitch value in the lane coordinate |
yaw | yaw value in the lane coordinate |
hdmap_utils_ptr | pointer to HdmapUtils |
const simulation_api_schema::DetectionSensorConfiguration traffic_simulator::helper::constructDetectionSensorConfiguration | ( | const std::string & | entity, |
const std::string & | architecture_type, | ||
const double | update_duration, | ||
const double | range = 300.0 , |
||
const bool | detect_all_objects_in_range = false , |
||
const double | pos_noise_stddev = 0 , |
||
const int | random_seed = 0 , |
||
const double | probability_of_lost = 0 , |
||
const double | object_recognition_delay = 0 , |
||
const double | object_recognition_ground_truth_delay = 0 |
||
) |
LaneletPose traffic_simulator::helper::constructLaneletPose | ( | lanelet::Id | lanelet_id, |
double | s, | ||
double | offset = 0 , |
||
double | roll = 0 , |
||
double | pitch = 0 , |
||
double | yaw = 0 |
||
) |
helper function for constructing lanelet pose
lanelet_id | lanelet id |
s | s value in lane coordinate |
offset | offset value in lane coordinate |
roll | roll value in the lane coordinate |
pitch | pitch value in the lane coordinate |
yaw | yaw value in the lane coordinate |
const simulation_api_schema::LidarConfiguration traffic_simulator::helper::constructLidarConfiguration | ( | const LidarType | type, |
const std::string & | entity, | ||
const std::string & | architecture_type, | ||
const double | lidar_sensor_delay = 0 , |
||
const double | horizontal_resolution = 1.0 / 180.0 * M_PI |
||
) |
geometry_msgs::msg::Pose traffic_simulator::helper::constructPose | ( | double | x, |
double | y, | ||
double | z, | ||
double | roll, | ||
double | pitch, | ||
double | yaw | ||
) |
helper function for constructing pose
x | x value in position |
y | y value in position |
z | z value in position |
roll | roll value in orientation |
pitch | pitch value in orientation |
yaw | yaw value in orientation |
geometry_msgs::msg::Vector3 traffic_simulator::helper::constructRPY | ( | double | roll = 0 , |
double | pitch = 0 , |
||
double | yaw = 0 |
||
) |
helper function for constructing rpy
roll | roll value of the orientation |
pitch | pitch value of the orientation |
yaw | yaw value of the orientation |
geometry_msgs::msg::Vector3 traffic_simulator::helper::constructRPYfromQuaternion | ( | geometry_msgs::msg::Quaternion | quaternion | ) |
helper function for constructing rpy
quaternion | quaternion class |
std::vector<T> traffic_simulator::helper::getUniqueValues | ( | const std::vector< T > & | input_vector | ) |
helper function for creating vector without duplicates, with preserved order
vector | input std::vector |