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.
object_detection_tracking_node.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2019-2021 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
17
18namespace object{
19
20 using std::placeholders::_1;
21 using std::placeholders::_2;
22 using std::placeholders::_3;
23
25 : carma_ros2_utils::CarmaLifecycleNode(options),
26 object_worker_(
27 std::bind(&ObjectDetectionTrackingNode::publishObject, this, _1),
28 std::bind(&ObjectDetectionTrackingNode::lookupTransform, this, _1, _2, _3),
29 get_node_logging_interface()
30 ),
31 tfBuffer_(get_clock()),
32 tfListener_(tfBuffer_)
33 {
34 map_frame_ = this->declare_parameter<std::string>("map_frame", map_frame_);
35 }
36
37 carma_ros2_utils::CallbackReturn ObjectDetectionTrackingNode::handle_on_configure(const rclcpp_lifecycle::State &) {
38
39 // Load parameters
40 this->get_parameter<std::string>("map_frame", map_frame_);
42
43 this->add_on_set_parameters_callback(
44 [this](auto param_vec) {
45
46 auto error = update_params<std::string>({ {"map_frame", map_frame_} }, param_vec);
47
48 rcl_interfaces::msg::SetParametersResult result;
49
50 result.successful = !error;
51
52 if (error) {
53 result.reason = error.get();
54 } else {
56 }
57
58 return result;
59 }
60 );
61
62
63 // Setup pub/sub
64 autoware_obj_sub_= create_subscription<autoware_auto_msgs::msg::TrackedObjects>("detected_objects",10,
66 );
67
68 carma_obj_pub_= create_publisher<carma_perception_msgs::msg::ExternalObjectList>("external_objects", 10);
69
70 return CallbackReturn::SUCCESS;
71 }
72
73 void ObjectDetectionTrackingNode::publishObject(const carma_perception_msgs::msg::ExternalObjectList& obj_msg)
74 {
75 carma_obj_pub_->publish(obj_msg);
76 }
77
78 boost::optional<geometry_msgs::msg::TransformStamped>
79 ObjectDetectionTrackingNode::lookupTransform(const std::string& parent, const std::string& child, const rclcpp::Time& stamp) {
80 try {
81
82 return tfBuffer_.lookupTransform(parent ,child, stamp);
83
84 } catch (tf2::TransformException &ex) {
85
86 RCLCPP_WARN_STREAM(get_logger(), "Failed to find transform with exception " << ex.what());
87 return boost::none;
88 }
89 }
90
91
92
93}//object
94
95#include "rclcpp_components/register_node_macro.hpp"
96
97// Register the component with class_loader
98RCLCPP_COMPONENTS_REGISTER_NODE(object::ObjectDetectionTrackingNode)
carma_ros2_utils::SubPtr< autoware_auto_msgs::msg::TrackedObjects > autoware_obj_sub_
void publishObject(const carma_perception_msgs::msg::ExternalObjectList &obj_msg)
Callback to publish ObjectList.
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
boost::optional< geometry_msgs::msg::TransformStamped > lookupTransform(const std::string &parent, const std::string &child, const rclcpp::Time &stamp)
Callback to lookup a transform between two frames.
ObjectDetectionTrackingNode(const rclcpp::NodeOptions &)
ObjectDetectionTrackingNode constructor.
carma_ros2_utils::PubPtr< carma_perception_msgs::msg::ExternalObjectList > carma_obj_pub_
void detectedObjectCallback(autoware_auto_msgs::msg::TrackedObjects::UniquePtr msg)
detectedObjectCallback populates detected object along with its velocity,yaw, yaw_rate and static/dyn...