Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
bsm_generator_worker.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2019-2022 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#pragma once
18
19#include <rclcpp/rclcpp.hpp>
20#include <functional>
21#include <vector>
22#include <climits>
23#include <random>
24#include <tf2/LinearMath/Transform.h>
25#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
26
27
28namespace bsm_generator
29{
30
36 {
37 public:
38
43
49 uint8_t getNextMsgCount();
50
58 std::vector<uint8_t> getMsgId(const rclcpp::Time now, double secs);
59
65 uint16_t getSecMark(const rclcpp::Time now);
66
73 float getSpeedInRange(const double speed);
74
81 float getSteerWheelAngleInRange(const double angle);
82
89 float getLongAccelInRange(const float accel);
90
97 float getYawRateInRange(const double yaw_rate);
98
104 uint8_t getBrakeAppliedStatus(const double brake);
105
112 float getHeadingInRange(const float heading);
116 float getHeading(const geometry_msgs::msg::Quaternion & quaternion);
117
118 private:
119 // Random number generator for BSM id
120 std::default_random_engine generator_;
121
122 // BSM message counter value
123 uint8_t msg_count_ {0};
124
125 // Random ID used to generate a new random BSM Message ID
126 int random_id_ {0};
127
128 // Variable to track the time that the last randomized BSM Message ID was generated
130
131 // Variable to track whether this object's getMsgId() method is being called for the first time,
132 // so that 'last_id_generation_time_' can initialized with the proper time source
133 bool first_msg_id_ = true;
134 };
135} // namespace bsm_generator
The class containing the primary business logic for the BSM Generator Package.
float getHeading(const geometry_msgs::msg::Quaternion &quaternion)
Function to convert a quaternion to a positive NED heading value.
std::default_random_engine generator_
float getSteerWheelAngleInRange(const double angle)
Function to apply minimum and maximum limits to a steering wheel angle value. Minimum limit is -189....
float getYawRateInRange(const double yaw_rate)
Function to apply minimum and maximum limits to a yaw rate value. Minimum limit is -327....
float getSpeedInRange(const double speed)
Function to apply minimum and maximum limits to a speed value. Minimum limit is 0....
BSMGeneratorWorker()
Default Constructor for BSMGeneratorWorker.
float getLongAccelInRange(const float accel)
Function to apply minimum and maximum limits to a longitudinal acceleration value....
std::vector< uint8_t > getMsgId(const rclcpp::Time now, double secs)
Function to obtain the current BSM message ID. The ID is updated to a new random BSM message ID every...
uint8_t getNextMsgCount()
Function to increment the BSM message counter and obtain the new counter value. Counter restarts at 0...
uint8_t getBrakeAppliedStatus(const double brake)
Function to convert the current applied brake status to a value used within the BSM message.
uint16_t getSecMark(const rclcpp::Time now)
Function to obtain the 'milliseconds' mark of the provided time within the last minute.
float getHeadingInRange(const float heading)
Function to apply minimum and maximum limits to a vehicle heading value. Minimum limit is 0....