15#ifndef MOTION_COMPUTATION__MOTION_COMPUTATION_NODE_HPP_
16#define MOTION_COMPUTATION__MOTION_COMPUTATION_NODE_HPP_
18#include <lanelet2_extension/projection/local_frame_projector.h>
19#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
26#include <carma_ros2_utils/carma_lifecycle_node.hpp>
27#include <rclcpp/rclcpp.hpp>
29#include <carma_perception_msgs/msg/external_object_list.hpp>
30#include <carma_v2x_msgs/msg/mobility_path.hpp>
31#include <std_msgs/msg/string.hpp>
43 carma_ros2_utils::SubPtr<carma_perception_msgs::msg::ExternalObjectList>
motion_comp_sub_;
45 carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::BSM>
bsm_sub_;
46 carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::PSM>
psm_sub_;
50 carma_ros2_utils::PubPtr<carma_perception_msgs::msg::ExternalObjectList>
carma_obj_pub_;
68 const std::vector<rclcpp::Parameter> & parameters);
74 void publishObject(
const carma_perception_msgs::msg::ExternalObjectList & obj_pred_msg)
const;
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_
The class containing the primary business logic for the Motion Computation Package.
Stuct containing the algorithm configuration values for motion_computation.