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.
motion_computation_node.cpp
Go to the documentation of this file.
1// Copyright 2019-2023 Leidos
2//
3// Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except
4// in compliance with the License. You may obtain a copy of the License at
5//
6// http://www.apache.org/licenses/LICENSE-2.0
7//
8// Unless required by applicable law or agreed to in writing, software distributed under the License
9// is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express
10// or implied. See the License for the specific language governing permissions and limitations under
11// the License.
12
14
15#include <vector>
16
17namespace motion_computation
18{
19namespace std_ph = std::placeholders;
20
21MotionComputationNode::MotionComputationNode(const rclcpp::NodeOptions & options)
22: carma_ros2_utils::CarmaLifecycleNode(options),
23 motion_worker_(
24 std::bind(&MotionComputationNode::publishObject, this, std_ph::_1),
25 get_node_logging_interface(), get_node_clock_interface())
26{
27 // Create initial config
28 config_ = Config();
29
30 // Declare parameters
32 declare_parameter<double>("prediction_time_step", config_.prediction_time_step);
34 declare_parameter<double>("prediction_period", config_.prediction_period);
36 declare_parameter<double>("cv_x_accel_noise", config_.cv_x_accel_noise);
38 declare_parameter<double>("cv_y_accel_noise", config_.cv_y_accel_noise);
40 declare_parameter<double>("prediction_process_noise_max", config_.prediction_process_noise_max);
41 config_.prediction_confidence_drop_rate = declare_parameter<double>(
42 "prediction_confidence_drop_rate", config_.prediction_confidence_drop_rate);
44 declare_parameter<bool>("enable_bsm_processing", config_.enable_bsm_processing);
46 declare_parameter<bool>("enable_psm_processing", config_.enable_psm_processing);
47 config_.enable_mobility_path_processing = declare_parameter<bool>(
48 "enable_mobility_path_processing", config_.enable_mobility_path_processing);
50 declare_parameter<bool>("enable_sensor_processing", config_.enable_sensor_processing);
52 declare_parameter<bool>("enable_ctrv_for_unknown_obj", config_.enable_ctrv_for_unknown_obj);
53 config_.enable_ctrv_for_motorcycle_obj = declare_parameter<bool>(
54 "enable_ctrv_for_motorcycle_obj", config_.enable_ctrv_for_motorcycle_obj);
55 config_.enable_ctrv_for_small_vehicle_obj = declare_parameter<bool>(
56 "enable_ctrv_for_small_vehicle_obj", config_.enable_ctrv_for_small_vehicle_obj);
57 config_.enable_ctrv_for_large_vehicle_obj = declare_parameter<bool>(
58 "enable_ctrv_for_large_vehicle_obj", config_.enable_ctrv_for_large_vehicle_obj);
59 config_.enable_ctrv_for_pedestrian_obj = declare_parameter<bool>(
60 "enable_ctrv_for_pedestrian_obj", config_.enable_ctrv_for_pedestrian_obj);
61}
62
63rcl_interfaces::msg::SetParametersResult MotionComputationNode::parameter_update_callback(
64 const std::vector<rclcpp::Parameter> & parameters)
65{
66 auto error = update_params<double>(
67 {{"prediction_time_step", config_.prediction_time_step},
68 {"prediction_period", config_.prediction_period},
69 {"cv_x_accel_noise", config_.cv_x_accel_noise},
70 {"cv_y_accel_noise", config_.cv_y_accel_noise},
71 {"prediction_process_noise_max", config_.prediction_process_noise_max},
72 {"prediction_confidence_drop_rate", config_.prediction_confidence_drop_rate}},
73 parameters);
74
75 auto error_2 = update_params<bool>(
76 {{"enable_bsm_processing", config_.enable_bsm_processing},
77 {"enable_psm_processing", config_.enable_psm_processing},
78 {"enable_mobility_path_processing", config_.enable_mobility_path_processing},
79 {"enable_sensor_processing", config_.enable_sensor_processing},
80 {"enable_ctrv_for_unknown_obj", config_.enable_ctrv_for_unknown_obj},
81 {"enable_ctrv_for_motorcycle_obj", config_.enable_ctrv_for_motorcycle_obj},
82 {"enable_ctrv_for_small_vehicle_obj", config_.enable_ctrv_for_small_vehicle_obj},
83 {"enable_ctrv_for_large_vehicle_obj", config_.enable_ctrv_for_large_vehicle_obj},
84 {"enable_ctrv_for_pedestrian_obj", config_.enable_ctrv_for_pedestrian_obj}},
85 parameters);
86
87 rcl_interfaces::msg::SetParametersResult result;
88
89 result.successful = !error && !error_2;
90
91 if (result.successful) {
92 // Set motion_worker_'s prediction parameters
106 }
107
108 return result;
109}
110
111carma_ros2_utils::CallbackReturn MotionComputationNode::handle_on_configure(
112 const rclcpp_lifecycle::State &)
113{
114 RCLCPP_INFO_STREAM(get_logger(), "MotionComputationNode trying to configure");
115
116 // Reset config
117 config_ = Config();
118
119 // Load parameters
120 get_parameter<double>("prediction_time_step", config_.prediction_time_step);
121 get_parameter<double>("prediction_period", config_.prediction_period);
122 get_parameter<double>("cv_x_accel_noise", config_.cv_x_accel_noise);
123 get_parameter<double>("cv_y_accel_noise", config_.cv_y_accel_noise);
124 get_parameter<double>("prediction_process_noise_max", config_.prediction_process_noise_max);
125 get_parameter<double>("prediction_confidence_drop_rate", config_.prediction_confidence_drop_rate);
126 get_parameter<bool>("enable_bsm_processing", config_.enable_bsm_processing);
127 get_parameter<bool>("enable_psm_processing", config_.enable_psm_processing);
128 get_parameter<bool>("enable_mobility_path_processing", config_.enable_mobility_path_processing);
129 get_parameter<bool>("enable_sensor_processing", config_.enable_sensor_processing);
130 get_parameter<bool>("enable_ctrv_for_unknown_obj", config_.enable_ctrv_for_unknown_obj);
131 get_parameter<bool>("enable_ctrv_for_motorcycle_obj", config_.enable_ctrv_for_motorcycle_obj);
132 get_parameter<bool>(
133 "enable_ctrv_for_small_vehicle_obj", config_.enable_ctrv_for_small_vehicle_obj);
134 get_parameter<bool>(
135 "enable_ctrv_for_large_vehicle_obj", config_.enable_ctrv_for_large_vehicle_obj);
136 get_parameter<bool>("enable_ctrv_for_pedestrian_obj", config_.enable_ctrv_for_pedestrian_obj);
137
138 RCLCPP_INFO_STREAM(get_logger(), "Loaded params: " << config_);
139
140 // Register runtime parameter update callback
141 add_on_set_parameters_callback(
142 std::bind(&MotionComputationNode::parameter_update_callback, this, std_ph::_1));
143
144 // Setup subscribers
145 motion_comp_sub_ = create_subscription<carma_perception_msgs::msg::ExternalObjectList>(
146 "external_objects", 1,
148
149 mobility_path_sub_ = create_subscription<carma_v2x_msgs::msg::MobilityPath>(
150 "incoming_mobility_path", 100,
152
153 bsm_sub_ = create_subscription<carma_v2x_msgs::msg::BSM>(
154 "incoming_bsm", 100,
155 std::bind(&MotionComputationWorker::bsmCallback, &motion_worker_, std_ph::_1));
156
157 psm_sub_ = create_subscription<carma_v2x_msgs::msg::PSM>(
158 "incoming_psm", 100,
159 std::bind(&MotionComputationWorker::psmCallback, &motion_worker_, std_ph::_1));
160
161 georeference_sub_ = create_subscription<std_msgs::msg::String>(
162 "georeference", 1,
164
165 // Setup publishers
166 carma_obj_pub_ = create_publisher<carma_perception_msgs::msg::ExternalObjectList>(
167 "external_object_predictions", 2);
168
169 // Set motion_worker_'s prediction parameters
179
180 // Return success if everything initialized successfully
181 return CallbackReturn::SUCCESS;
182}
183
185 const carma_perception_msgs::msg::ExternalObjectList & obj_pred_msg) const
186{
187 carma_obj_pub_->publish(obj_pred_msg);
188}
189
190} // namespace motion_computation
191
192#include "rclcpp_components/register_node_macro.hpp"
193// Register the component with class_loader
194RCLCPP_COMPONENTS_REGISTER_NODE(motion_computation::MotionComputationNode)
The class responsible for publishing external object predictions.
void publishObject(const carma_perception_msgs::msg::ExternalObjectList &obj_pred_msg) const
Function to publish ExternalObjectList.
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::BSM > bsm_sub_
carma_ros2_utils::SubPtr< std_msgs::msg::String > georeference_sub_
MotionComputationNode(const rclcpp::NodeOptions &)
MotionComputationNode constructor.
carma_ros2_utils::SubPtr< carma_perception_msgs::msg::ExternalObjectList > motion_comp_sub_
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::MobilityPath > mobility_path_sub_
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Function callback for dynamic parameter updates.
carma_ros2_utils::PubPtr< carma_perception_msgs::msg::ExternalObjectList > carma_obj_pub_
carma_ros2_utils::SubPtr< carma_v2x_msgs::msg::PSM > psm_sub_
void georeferenceCallback(const std_msgs::msg::String::UniquePtr msg)
Callback for map projection string to define lat/lon -> map conversion.
void predictionLogic(carma_perception_msgs::msg::ExternalObjectList::UniquePtr obj_list)
Function to populate duplicated detected objects along with their velocity, yaw, yaw_rate and static/...
void setDetectionMotionModelFlags(bool enable_ctrv_for_unknown_obj, bool enable_ctrv_for_motorcycle_obj, bool enable_ctrv_for_small_vehicle_obj, bool enable_ctrv_for_large_vehicle_obj, bool enable_ctrv_for_pedestrian_obj)
void psmCallback(const carma_v2x_msgs::msg::PSM::UniquePtr msg)
void bsmCallback(const carma_v2x_msgs::msg::BSM::UniquePtr msg)
void setDetectionInputFlags(bool enable_sensor_processing, bool enable_bsm_processing, bool enable_psm_processing, bool enable_mobility_path_processing)
void mobilityPathCallback(const carma_v2x_msgs::msg::MobilityPath::UniquePtr msg)
Stuct containing the algorithm configuration values for motion_computation.