scenario_simulator_v2 C++ API
Classes | Enumerations | Functions
traffic_simulator::helper Namespace Reference

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...
 
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)
 

Enumeration Type Documentation

◆ LidarType

Enumerator
VLP16 
VLP32 

Function Documentation

◆ constructActionStatus()

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

Parameters
linear_vellinear velocity
angular_velangular velocity
linear_accellinear acceleration
angular_accelangular acceleration
Returns
traffic_simulator_msgs::msg::ActionStatus

◆ constructDetectionSensorConfiguration()

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 
)

◆ constructLaneletPose()

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

Parameters
lanelet_idlanelet id
ss value in lane coordinate
offsetoffset value in lane coordinate
rollroll value in the lane coordinate
pitchpitch value in the lane coordinate
yawyaw value in the lane coordinate
Returns
LaneletPose

◆ constructLidarConfiguration()

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 
)

◆ constructPose()

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

Parameters
xx value in position
yy value in position
zz value in position
rollroll value in orientation
pitchpitch value in orientation
yawyaw value in orientation
Returns
geometry_msgs::msg::Pose

◆ constructRPY()

geometry_msgs::msg::Vector3 traffic_simulator::helper::constructRPY ( double  roll = 0,
double  pitch = 0,
double  yaw = 0 
)

helper function for constructing rpy

Parameters
rollroll value of the orientation
pitchpitch value of the orientation
yawyaw value of the orientation
Returns
geometry_msgs::msg::Vector3 RPY values

◆ constructRPYfromQuaternion()

geometry_msgs::msg::Vector3 traffic_simulator::helper::constructRPYfromQuaternion ( geometry_msgs::msg::Quaternion  quaternion)

helper function for constructing rpy

Parameters
quaternionquaternion class
Returns
geometry_msgs::msg::Vector3 RPY value

◆ getUniqueValues()

template<typename T >
std::vector<T> traffic_simulator::helper::getUniqueValues ( const std::vector< T > &  input_vector)

helper function for creating vector without duplicates, with preserved order

Parameters
vectorinput std::vector
Returns
new std::vector without duplicates and with relative order preserved