19namespace std_ph = std::placeholders;
22: carma_ros2_utils::CarmaLifecycleNode(options),
25 get_node_logging_interface(), get_node_clock_interface())
64 const std::vector<rclcpp::Parameter> & parameters)
66 auto error = update_params<double>(
75 auto error_2 = update_params<bool>(
87 rcl_interfaces::msg::SetParametersResult result;
89 result.successful = !error && !error_2;
91 if (result.successful) {
112 const rclcpp_lifecycle::State &)
114 RCLCPP_INFO_STREAM(get_logger(),
"MotionComputationNode trying to configure");
138 RCLCPP_INFO_STREAM(get_logger(),
"Loaded params: " <<
config_);
141 add_on_set_parameters_callback(
145 motion_comp_sub_ = create_subscription<carma_perception_msgs::msg::ExternalObjectList>(
146 "external_objects", 1,
150 "incoming_mobility_path", 100,
153 bsm_sub_ = create_subscription<carma_v2x_msgs::msg::BSM>(
157 psm_sub_ = create_subscription<carma_v2x_msgs::msg::PSM>(
166 carma_obj_pub_ = create_publisher<carma_perception_msgs::msg::ExternalObjectList>(
167 "external_object_predictions", 2);
181 return CallbackReturn::SUCCESS;
185 const carma_perception_msgs::msg::ExternalObjectList & obj_pred_msg)
const
192#include "rclcpp_components/register_node_macro.hpp"
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.
MotionComputationWorker motion_worker_
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 > ¶meters)
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 setConfidenceDropRate(double drop_rate)
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 setYAccelerationNoise(double noise)
void setDetectionInputFlags(bool enable_sensor_processing, bool enable_bsm_processing, bool enable_psm_processing, bool enable_mobility_path_processing)
void setXAccelerationNoise(double noise)
void setPredictionPeriod(double period)
void mobilityPathCallback(const carma_v2x_msgs::msg::MobilityPath::UniquePtr msg)
void setProcessNoiseMax(double noise_max)
void setPredictionTimeStep(double time_step)
Stuct containing the algorithm configuration values for motion_computation.
bool enable_ctrv_for_small_vehicle_obj
bool enable_ctrv_for_motorcycle_obj
bool enable_sensor_processing
bool enable_ctrv_for_pedestrian_obj
bool enable_ctrv_for_large_vehicle_obj
double prediction_confidence_drop_rate
bool enable_ctrv_for_unknown_obj
bool enable_psm_processing
bool enable_bsm_processing
double prediction_time_step
double prediction_process_noise_max
bool enable_mobility_path_processing