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.hpp
Go to the documentation of this file.
1// Copyright 2019-2023 Leidos
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef MOTION_COMPUTATION__MOTION_COMPUTATION_NODE_HPP_
16#define MOTION_COMPUTATION__MOTION_COMPUTATION_NODE_HPP_
17
18#include <lanelet2_extension/projection/local_frame_projector.h>
19#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
20
21#include <functional>
22#include <vector>
23
26#include <carma_ros2_utils/carma_lifecycle_node.hpp>
27#include <rclcpp/rclcpp.hpp>
28
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>
32
33namespace motion_computation
34{
39class MotionComputationNode : public carma_ros2_utils::CarmaLifecycleNode
40{
41private:
42 // Subscribers
43 carma_ros2_utils::SubPtr<carma_perception_msgs::msg::ExternalObjectList> motion_comp_sub_;
44 carma_ros2_utils::SubPtr<carma_v2x_msgs::msg::MobilityPath> mobility_path_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_;
47 carma_ros2_utils::SubPtr<std_msgs::msg::String> georeference_sub_;
48
49 // Publishers
50 carma_ros2_utils::PubPtr<carma_perception_msgs::msg::ExternalObjectList> carma_obj_pub_;
51
52 // MotionComputationWorker class object
54
55 // Node configuration
57
58public:
62 explicit MotionComputationNode(const rclcpp::NodeOptions &);
63
67 rcl_interfaces::msg::SetParametersResult parameter_update_callback(
68 const std::vector<rclcpp::Parameter> & parameters);
69
74 void publishObject(const carma_perception_msgs::msg::ExternalObjectList & obj_pred_msg) const;
75
77 // Overrides
79 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &);
80};
81
82} // namespace motion_computation
83
84#endif // MOTION_COMPUTATION__MOTION_COMPUTATION_NODE_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.
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_
The class containing the primary business logic for the Motion Computation Package.
Stuct containing the algorithm configuration values for motion_computation.