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::BSMGenerator Class Reference

The class responsible for publishing BSM messages. More...

#include <bsm_generator_node.hpp>

Inheritance diagram for bsm_generator::BSMGenerator:
Inheritance graph
Collaboration diagram for bsm_generator::BSMGenerator:
Collaboration graph

Public Member Functions

 BSMGenerator (const rclcpp::NodeOptions &)
 BSMGenerator constructor. More...
 
rcl_interfaces::msg::SetParametersResult parameter_update_callback (const std::vector< rclcpp::Parameter > &parameters)
 Function callback for dynamic parameter updates. More...
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &)
 
carma_ros2_utils::CallbackReturn handle_on_activate (const rclcpp_lifecycle::State &)
 

Private Member Functions

void initializeBSM ()
 Function to fill the BSM message with initial default data. More...
 
void poseCallback (const geometry_msgs::msg::PoseStamped::UniquePtr msg)
 Callback to populate BSM message with longitude, latitude, and elevation data. More...
 
void accelCallback (const automotive_platform_msgs::msg::VelocityAccelCov::UniquePtr msg)
 Callback to populate BSM message with longitudinal acceleration data. More...
 
void yawCallback (const sensor_msgs::msg::Imu::UniquePtr msg)
 Callback to populate BSM message with yaw rate data. More...
 
void gearCallback (const j2735_v2x_msgs::msg::TransmissionState::UniquePtr msg)
 Callback to populate BSM message with transmission state data. More...
 
void speedCallback (const geometry_msgs::msg::TwistStamped::UniquePtr msg)
 Callback to populate BSM message with vehicle speed data. More...
 
void steerWheelAngleCallback (const std_msgs::msg::Float64::UniquePtr msg)
 Callback to populate BSM message with vehicle steering wheel angle data. More...
 
void brakeCallback (const std_msgs::msg::Float64::UniquePtr msg)
 Callback to populate BSM message with vehicle applied brake status. More...
 
void headingCallback (const gps_msgs::msg::GPSFix::UniquePtr msg)
 Callback to populate BSM message with vehicle heading data. More...
 
void georeferenceCallback (const std_msgs::msg::String::UniquePtr msg)
 Callback for map projection string to define lat/lon -> map conversion. More...
 
void generateBSM ()
 Timer callback, which publishes a BSM. More...
 

Private Attributes

carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > pose_sub_
 
carma_ros2_utils::SubPtr< automotive_platform_msgs::msg::VelocityAccelCov > accel_sub_
 
carma_ros2_utils::SubPtr< sensor_msgs::msg::Imu > yaw_sub_
 
carma_ros2_utils::SubPtr< j2735_v2x_msgs::msg::TransmissionState > gear_sub_
 
carma_ros2_utils::SubPtr< geometry_msgs::msg::TwistStamped > speed_sub_
 
carma_ros2_utils::SubPtr< std_msgs::msg::Float64 > steer_wheel_angle_sub_
 
carma_ros2_utils::SubPtr< std_msgs::msg::Float64 > brake_sub_
 
carma_ros2_utils::SubPtr< gps_msgs::msg::GPSFix > heading_sub_
 
carma_ros2_utils::SubPtr< std_msgs::msg::String > georeference_sub_
 
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::BSM > bsm_pub_
 
rclcpp::TimerBase::SharedPtr timer_
 
Config config_
 
std::shared_ptr< BSMGeneratorWorkerworker
 
carma_v2x_msgs::msg::BSM bsm_
 
std::string georeference_ {""}
 
std::shared_ptr< lanelet::projection::LocalFrameProjector > map_projector_
 
std::vector< uint8_t > bsm_message_id_
 

Detailed Description

The class responsible for publishing BSM messages.

Definition at line 45 of file bsm_generator_node.hpp.

Constructor & Destructor Documentation

◆ BSMGenerator()

bsm_generator::BSMGenerator::BSMGenerator ( const rclcpp::NodeOptions &  options)
explicit

BSMGenerator constructor.

Definition at line 22 of file bsm_generator_node.cpp.

23 : carma_ros2_utils::CarmaLifecycleNode(options)
24 {
25 // Create initial config
26 config_ = Config();
27
28 // Declare parameters
29 config_.bsm_generation_frequency = declare_parameter<double>("bsm_generation_frequency", config_.bsm_generation_frequency);
30 config_.bsm_id_change_period = declare_parameter<double>("bsm_id_change_period", config_.bsm_id_change_period);
31 config_.bsm_id_rotation_enabled = declare_parameter<bool>("bsm_id_rotation_enabled", config_.bsm_id_rotation_enabled);
32 config_.bsm_message_id = declare_parameter<int>("bsm_message_id", config_.bsm_message_id);
33 config_.vehicle_length = declare_parameter<double>("vehicle_length", config_.vehicle_length);
34 config_.vehicle_width = declare_parameter<double>("vehicle_width", config_.vehicle_width);
35 }

References bsm_generator::Config::bsm_generation_frequency, bsm_generator::Config::bsm_id_change_period, bsm_generator::Config::bsm_id_rotation_enabled, bsm_generator::Config::bsm_message_id, config_, bsm_generator::Config::vehicle_length, and bsm_generator::Config::vehicle_width.

Member Function Documentation

◆ accelCallback()

void bsm_generator::BSMGenerator::accelCallback ( const automotive_platform_msgs::msg::VelocityAccelCov::UniquePtr  msg)
private

Callback to populate BSM message with longitudinal acceleration data.

Parameters
msgLatest acceleration message

Definition at line 154 of file bsm_generator_node.cpp.

155 {
156 bsm_.core_data.accel_set.longitudinal = worker->getLongAccelInRange(msg->accleration);
157 bsm_.core_data.accel_set.presence_vector = bsm_.core_data.accel_set.presence_vector | bsm_.core_data.accel_set.ACCELERATION_AVAILABLE;
158 }
std::shared_ptr< BSMGeneratorWorker > worker
carma_v2x_msgs::msg::BSM bsm_

References bsm_, and worker.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ brakeCallback()

void bsm_generator::BSMGenerator::brakeCallback ( const std_msgs::msg::Float64::UniquePtr  msg)
private

Callback to populate BSM message with vehicle applied brake status.

Parameters
msgLatest brake status message

Definition at line 166 of file bsm_generator_node.cpp.

167 {
168 bsm_.core_data.brakes.wheel_brakes.brake_applied_status = worker->getBrakeAppliedStatus(msg->data);
169 }

References bsm_, and worker.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ gearCallback()

void bsm_generator::BSMGenerator::gearCallback ( const j2735_v2x_msgs::msg::TransmissionState::UniquePtr  msg)
private

Callback to populate BSM message with transmission state data.

Parameters
msgLatest transmissio state message

Definition at line 143 of file bsm_generator_node.cpp.

144 {
145 bsm_.core_data.transmission.transmission_state = msg->transmission_state;
146 }

References bsm_.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ generateBSM()

void bsm_generator::BSMGenerator::generateBSM ( )
private

Timer callback, which publishes a BSM.

Definition at line 195 of file bsm_generator_node.cpp.

196 {
197 bsm_.header.stamp = this->now();
198 bsm_.core_data.msg_count = worker->getNextMsgCount();
199
201 bsm_.core_data.id = worker->getMsgId( this->now(), config_.bsm_id_change_period);
202 else
203 {
204 std::vector<uint8_t> id(4);
205 for(int i = 0; i < id.size(); ++i)
206 {
207 id[i] = config_.bsm_message_id >> (8 * i);
208 }
209 bsm_.core_data.id = id;
210 }
211
212 bsm_.core_data.sec_mark = worker->getSecMark( this->now() );
213 bsm_.core_data.presence_vector = bsm_.core_data.presence_vector | bsm_.core_data.SEC_MARK_AVAILABLE;
214 // currently the accuracy is not available because ndt_matching does not provide accuracy measurement
215 bsm_.core_data.accuracy.presence_vector = 0;
216 bsm_pub_->publish(bsm_);
217 }
carma_ros2_utils::PubPtr< carma_v2x_msgs::msg::BSM > bsm_pub_

References bsm_, bsm_generator::Config::bsm_id_change_period, bsm_generator::Config::bsm_id_rotation_enabled, bsm_generator::Config::bsm_message_id, bsm_pub_, config_, process_bag::i, and worker.

Referenced by handle_on_activate().

Here is the caller graph for this function:

◆ georeferenceCallback()

void bsm_generator::BSMGenerator::georeferenceCallback ( const std_msgs::msg::String::UniquePtr  msg)
private

Callback for map projection string to define lat/lon -> map conversion.

Parameters
msgThe proj string defining the projection.

Definition at line 127 of file bsm_generator_node.cpp.

128 {
129 // Build projector from proj string
130 if (georeference_ != msg->data)
131 {
132 georeference_ = msg->data;
133 map_projector_ = std::make_shared<lanelet::projection::LocalFrameProjector>(msg->data.c_str());
134 }
135 }
std::shared_ptr< lanelet::projection::LocalFrameProjector > map_projector_

References georeference_, and map_projector_.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ handle_on_activate()

carma_ros2_utils::CallbackReturn bsm_generator::BSMGenerator::handle_on_activate ( const rclcpp_lifecycle::State &  prev_state)

Definition at line 107 of file bsm_generator_node.cpp.

108 {
109 // Timer setup for generating a BSM
110 int bsm_generation_period_ms = (1 / config_.bsm_generation_frequency) * 1000; // Conversion from frequency (Hz) to milliseconds time period
111 timer_ = create_timer(get_clock(),
112 std::chrono::milliseconds(bsm_generation_period_ms),
113 std::bind(&BSMGenerator::generateBSM, this));
114
115 return CallbackReturn::SUCCESS;
116 }
void generateBSM()
Timer callback, which publishes a BSM.
rclcpp::TimerBase::SharedPtr timer_

References bsm_generator::Config::bsm_generation_frequency, config_, generateBSM(), and timer_.

Here is the call graph for this function:

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn bsm_generator::BSMGenerator::handle_on_configure ( const rclcpp_lifecycle::State &  )

Definition at line 55 of file bsm_generator_node.cpp.

56 {
57 RCLCPP_INFO_STREAM(get_logger(), "BSMGenerator trying to configure");
58
59 // Reset config
60 config_ = Config();
61
62 // Load parameters
63 get_parameter<double>("bsm_generation_frequency", config_.bsm_generation_frequency);
64 get_parameter<double>("bsm_id_change_period", config_.bsm_id_change_period);
65 get_parameter<bool>("bsm_id_rotation_enabled", config_.bsm_id_rotation_enabled);
66 get_parameter<int>("bsm_message_id", config_.bsm_message_id);
67 get_parameter<double>("vehicle_length", config_.vehicle_length);
68 get_parameter<double>("vehicle_width", config_.vehicle_width);
69
70 RCLCPP_INFO_STREAM(get_logger(), "Loaded params: " << config_);
71
72 // Register runtime parameter update callback
73 add_on_set_parameters_callback(std::bind(&BSMGenerator::parameter_update_callback, this, std_ph::_1));
74
75 // Setup subscribers
76 pose_sub_ = create_subscription<geometry_msgs::msg::PoseStamped>("pose", 1,
77 std::bind(&BSMGenerator::poseCallback, this, std_ph::_1));
78 accel_sub_ = create_subscription<automotive_platform_msgs::msg::VelocityAccelCov>("velocity_accel_cov", 1,
79 std::bind(&BSMGenerator::accelCallback, this, std_ph::_1));
80 yaw_sub_ = create_subscription<sensor_msgs::msg::Imu>("imu_raw", 1,
81 std::bind(&BSMGenerator::yawCallback, this, std_ph::_1));
82 gear_sub_ = create_subscription<j2735_v2x_msgs::msg::TransmissionState>("transmission_state", 1,
83 std::bind(&BSMGenerator::gearCallback, this, std_ph::_1));
84 speed_sub_ = create_subscription<geometry_msgs::msg::TwistStamped>("ekf_twist", 1,
85 std::bind(&BSMGenerator::speedCallback, this, std_ph::_1));
86 steer_wheel_angle_sub_ = create_subscription<std_msgs::msg::Float64>("steering_wheel_angle", 1,
87 std::bind(&BSMGenerator::steerWheelAngleCallback, this, std_ph::_1));
88 brake_sub_ = create_subscription<std_msgs::msg::Float64>("brake_position", 1,
89 std::bind(&BSMGenerator::brakeCallback, this, std_ph::_1));
90 heading_sub_ = create_subscription<gps_msgs::msg::GPSFix>("gnss_fix_fused", 1,
91 std::bind(&BSMGenerator::headingCallback, this, std_ph::_1));
92 georeference_sub_ = create_subscription<std_msgs::msg::String>("georeference", 1,
93 std::bind(&BSMGenerator::georeferenceCallback, this, std_ph::_1));
94
95 // Setup publishers
96 bsm_pub_ = create_publisher<carma_v2x_msgs::msg::BSM>("bsm_outbound", 5);
97
98 // Initialize the generated BSM message
100
101 worker = std::make_shared<BSMGeneratorWorker>();
102
103 // Return success if everthing initialized successfully
104 return CallbackReturn::SUCCESS;
105 }
carma_ros2_utils::SubPtr< std_msgs::msg::Float64 > brake_sub_
carma_ros2_utils::SubPtr< sensor_msgs::msg::Imu > yaw_sub_
carma_ros2_utils::SubPtr< automotive_platform_msgs::msg::VelocityAccelCov > accel_sub_
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Function callback for dynamic parameter updates.
carma_ros2_utils::SubPtr< gps_msgs::msg::GPSFix > heading_sub_
carma_ros2_utils::SubPtr< std_msgs::msg::String > georeference_sub_
carma_ros2_utils::SubPtr< j2735_v2x_msgs::msg::TransmissionState > gear_sub_
void georeferenceCallback(const std_msgs::msg::String::UniquePtr msg)
Callback for map projection string to define lat/lon -> map conversion.
void speedCallback(const geometry_msgs::msg::TwistStamped::UniquePtr msg)
Callback to populate BSM message with vehicle speed data.
void headingCallback(const gps_msgs::msg::GPSFix::UniquePtr msg)
Callback to populate BSM message with vehicle heading data.
void brakeCallback(const std_msgs::msg::Float64::UniquePtr msg)
Callback to populate BSM message with vehicle applied brake status.
carma_ros2_utils::SubPtr< std_msgs::msg::Float64 > steer_wheel_angle_sub_
void poseCallback(const geometry_msgs::msg::PoseStamped::UniquePtr msg)
Callback to populate BSM message with longitude, latitude, and elevation data.
carma_ros2_utils::SubPtr< geometry_msgs::msg::TwistStamped > speed_sub_
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > pose_sub_
void gearCallback(const j2735_v2x_msgs::msg::TransmissionState::UniquePtr msg)
Callback to populate BSM message with transmission state data.
void initializeBSM()
Function to fill the BSM message with initial default data.
void yawCallback(const sensor_msgs::msg::Imu::UniquePtr msg)
Callback to populate BSM message with yaw rate data.
void steerWheelAngleCallback(const std_msgs::msg::Float64::UniquePtr msg)
Callback to populate BSM message with vehicle steering wheel angle data.
void accelCallback(const automotive_platform_msgs::msg::VelocityAccelCov::UniquePtr msg)
Callback to populate BSM message with longitudinal acceleration data.

References accel_sub_, accelCallback(), brake_sub_, brakeCallback(), bsm_generator::Config::bsm_generation_frequency, bsm_generator::Config::bsm_id_change_period, bsm_generator::Config::bsm_id_rotation_enabled, bsm_generator::Config::bsm_message_id, bsm_pub_, config_, gear_sub_, gearCallback(), georeference_sub_, georeferenceCallback(), heading_sub_, headingCallback(), initializeBSM(), parameter_update_callback(), pose_sub_, poseCallback(), speed_sub_, speedCallback(), steer_wheel_angle_sub_, steerWheelAngleCallback(), bsm_generator::Config::vehicle_length, bsm_generator::Config::vehicle_width, worker, yaw_sub_, and yawCallback().

Here is the call graph for this function:

◆ headingCallback()

void bsm_generator::BSMGenerator::headingCallback ( const gps_msgs::msg::GPSFix::UniquePtr  msg)
private

Callback to populate BSM message with vehicle heading data.

Parameters
msgLatest GNSS message

Definition at line 189 of file bsm_generator_node.cpp.

190 {
191 bsm_.core_data.heading = worker->getHeadingInRange(static_cast<float>(msg->track));
192 bsm_.core_data.presence_vector = bsm_.core_data.presence_vector | bsm_.core_data.HEADING_AVAILABLE;
193 }

References bsm_, and worker.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ initializeBSM()

void bsm_generator::BSMGenerator::initializeBSM ( )
private

Function to fill the BSM message with initial default data.

Definition at line 118 of file bsm_generator_node.cpp.

119 {
120 bsm_.core_data.presence_vector = 0;
121 bsm_.core_data.size.vehicle_width = config_.vehicle_width;
122 bsm_.core_data.size.vehicle_length = config_.vehicle_length;
123 bsm_.core_data.size.presence_vector = bsm_.core_data.size.presence_vector | bsm_.core_data.size.VEHICLE_LENGTH_AVAILABLE;
124 bsm_.core_data.size.presence_vector = bsm_.core_data.size.presence_vector | bsm_.core_data.size.VEHICLE_WIDTH_AVAILABLE;
125 }

References bsm_, config_, bsm_generator::Config::vehicle_length, and bsm_generator::Config::vehicle_width.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ parameter_update_callback()

rcl_interfaces::msg::SetParametersResult bsm_generator::BSMGenerator::parameter_update_callback ( const std::vector< rclcpp::Parameter > &  parameters)

Function callback for dynamic parameter updates.

Definition at line 37 of file bsm_generator_node.cpp.

38 {
39 auto error = update_params<bool>({{"bsm_id_rotation_enabled", config_.bsm_id_rotation_enabled}}, parameters);
40 auto error_2 = update_params<int>({{"bsm_message_id", config_.bsm_message_id}}, parameters);
41 auto error_3 = update_params<double>({
42 {"bsm_generation_frequency", config_.bsm_generation_frequency},
43 {"bsm_id_change_period", config_.bsm_id_change_period},
44 {"vehicle_length", config_.vehicle_length},
45 {"vehicle_width", config_.vehicle_width}
46 }, parameters);
47
48 rcl_interfaces::msg::SetParametersResult result;
49
50 result.successful = !error && !error_2 && !error_3;
51
52 return result;
53 }

References bsm_generator::Config::bsm_generation_frequency, bsm_generator::Config::bsm_id_change_period, bsm_generator::Config::bsm_id_rotation_enabled, bsm_generator::Config::bsm_message_id, config_, bsm_generator::Config::vehicle_length, and bsm_generator::Config::vehicle_width.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ poseCallback()

void bsm_generator::BSMGenerator::poseCallback ( const geometry_msgs::msg::PoseStamped::UniquePtr  msg)
private

Callback to populate BSM message with longitude, latitude, and elevation data.

Parameters
msgLatest pose message

Definition at line 171 of file bsm_generator_node.cpp.

172 {
173 // Use pose message as an indicator of new location updates
174 if (!map_projector_) {
175 RCLCPP_DEBUG_STREAM(get_logger(), "Ignoring pose message as projection string has not been defined");
176 return;
177 }
178
179 lanelet::GPSPoint coord = map_projector_->reverse( { msg->pose.position.x, msg->pose.position.y, msg->pose.position.z } );
180
181 bsm_.core_data.longitude = coord.lon;
182 bsm_.core_data.latitude = coord.lat;
183 bsm_.core_data.elev = coord.ele;
184 bsm_.core_data.presence_vector = bsm_.core_data.presence_vector | bsm_.core_data.LONGITUDE_AVAILABLE;
185 bsm_.core_data.presence_vector = bsm_.core_data.presence_vector | bsm_.core_data.LATITUDE_AVAILABLE;
186 bsm_.core_data.presence_vector = bsm_.core_data.presence_vector | bsm_.core_data.ELEVATION_AVAILABLE;
187 }

References bsm_, and map_projector_.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ speedCallback()

void bsm_generator::BSMGenerator::speedCallback ( const geometry_msgs::msg::TwistStamped::UniquePtr  msg)
private

Callback to populate BSM message with vehicle speed data.

Parameters
msgLatest speed message

Definition at line 137 of file bsm_generator_node.cpp.

138 {
139 bsm_.core_data.speed = worker->getSpeedInRange(msg->twist.linear.x);
140 bsm_.core_data.presence_vector = bsm_.core_data.presence_vector | bsm_.core_data.SPEED_AVAILABLE;
141 }

References bsm_, and worker.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ steerWheelAngleCallback()

void bsm_generator::BSMGenerator::steerWheelAngleCallback ( const std_msgs::msg::Float64::UniquePtr  msg)
private

Callback to populate BSM message with vehicle steering wheel angle data.

Parameters
msgLatest steering wheel angle message

Definition at line 148 of file bsm_generator_node.cpp.

149 {
150 bsm_.core_data.angle = worker->getSteerWheelAngleInRange(msg->data);
151 bsm_.core_data.presence_vector = bsm_.core_data.presence_vector | bsm_.core_data.STEER_WHEEL_ANGLE_AVAILABLE;
152 }

References bsm_, and worker.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ yawCallback()

void bsm_generator::BSMGenerator::yawCallback ( const sensor_msgs::msg::Imu::UniquePtr  msg)
private

Callback to populate BSM message with yaw rate data.

Parameters
msgLatest IMU message

Definition at line 160 of file bsm_generator_node.cpp.

161 {
162 bsm_.core_data.accel_set.yaw_rate = worker->getYawRateInRange(static_cast<float>(msg->angular_velocity.z));
163 bsm_.core_data.accel_set.presence_vector = bsm_.core_data.accel_set.presence_vector | bsm_.core_data.accel_set.YAWRATE_AVAILABLE;
164 }

References bsm_, and worker.

Referenced by handle_on_configure().

Here is the caller graph for this function:

Member Data Documentation

◆ accel_sub_

carma_ros2_utils::SubPtr<automotive_platform_msgs::msg::VelocityAccelCov> bsm_generator::BSMGenerator::accel_sub_
private

Definition at line 51 of file bsm_generator_node.hpp.

Referenced by handle_on_configure().

◆ brake_sub_

carma_ros2_utils::SubPtr<std_msgs::msg::Float64> bsm_generator::BSMGenerator::brake_sub_
private

Definition at line 56 of file bsm_generator_node.hpp.

Referenced by handle_on_configure().

◆ bsm_

carma_v2x_msgs::msg::BSM bsm_generator::BSMGenerator::bsm_
private

◆ bsm_message_id_

std::vector<uint8_t> bsm_generator::BSMGenerator::bsm_message_id_
private

Definition at line 78 of file bsm_generator_node.hpp.

◆ bsm_pub_

carma_ros2_utils::PubPtr<carma_v2x_msgs::msg::BSM> bsm_generator::BSMGenerator::bsm_pub_
private

Definition at line 61 of file bsm_generator_node.hpp.

Referenced by generateBSM(), and handle_on_configure().

◆ config_

Config bsm_generator::BSMGenerator::config_
private

◆ gear_sub_

carma_ros2_utils::SubPtr<j2735_v2x_msgs::msg::TransmissionState> bsm_generator::BSMGenerator::gear_sub_
private

Definition at line 53 of file bsm_generator_node.hpp.

Referenced by handle_on_configure().

◆ georeference_

std::string bsm_generator::BSMGenerator::georeference_ {""}
private

Definition at line 75 of file bsm_generator_node.hpp.

Referenced by georeferenceCallback().

◆ georeference_sub_

carma_ros2_utils::SubPtr<std_msgs::msg::String> bsm_generator::BSMGenerator::georeference_sub_
private

Definition at line 58 of file bsm_generator_node.hpp.

Referenced by handle_on_configure().

◆ heading_sub_

carma_ros2_utils::SubPtr<gps_msgs::msg::GPSFix> bsm_generator::BSMGenerator::heading_sub_
private

Definition at line 57 of file bsm_generator_node.hpp.

Referenced by handle_on_configure().

◆ map_projector_

std::shared_ptr<lanelet::projection::LocalFrameProjector> bsm_generator::BSMGenerator::map_projector_
private

Definition at line 76 of file bsm_generator_node.hpp.

Referenced by georeferenceCallback(), and poseCallback().

◆ pose_sub_

carma_ros2_utils::SubPtr<geometry_msgs::msg::PoseStamped> bsm_generator::BSMGenerator::pose_sub_
private

Definition at line 50 of file bsm_generator_node.hpp.

Referenced by handle_on_configure().

◆ speed_sub_

carma_ros2_utils::SubPtr<geometry_msgs::msg::TwistStamped> bsm_generator::BSMGenerator::speed_sub_
private

Definition at line 54 of file bsm_generator_node.hpp.

Referenced by handle_on_configure().

◆ steer_wheel_angle_sub_

carma_ros2_utils::SubPtr<std_msgs::msg::Float64> bsm_generator::BSMGenerator::steer_wheel_angle_sub_
private

Definition at line 55 of file bsm_generator_node.hpp.

Referenced by handle_on_configure().

◆ timer_

rclcpp::TimerBase::SharedPtr bsm_generator::BSMGenerator::timer_
private

Definition at line 64 of file bsm_generator_node.hpp.

Referenced by handle_on_activate().

◆ worker

std::shared_ptr<BSMGeneratorWorker> bsm_generator::BSMGenerator::worker
private

◆ yaw_sub_

carma_ros2_utils::SubPtr<sensor_msgs::msg::Imu> bsm_generator::BSMGenerator::yaw_sub_
private

Definition at line 52 of file bsm_generator_node.hpp.

Referenced by handle_on_configure().


The documentation for this class was generated from the following files: