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.
frame_transformer_config.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2021 LEIDOS.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
7 * use this file except in compliance with the License. You may obtain a copy of
8 * the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15 * License for the specific language governing permissions and limitations under
16 * the License.
17 */
18
19#include <iostream>
20
21namespace frame_transformer
22{
23
27 struct Config
28 {
30 std::string target_frame = "base_link";
31
33 std::string message_type = "sensor_msgs/PointCloud2";
34
36 int queue_size = 1;
37
39 int timeout = 0;
40
41 // Stream operator for this config
42 friend std::ostream &operator<<(std::ostream &output, const Config &c)
43 {
44 output << "frame_transformer::Config { " << std::endl
45 << "target_frame: " << c.target_frame << std::endl
46 << "message_type: " << c.message_type << std::endl
47 << "queue_size: " << c.queue_size << std::endl
48 << "timeout: " << c.timeout << std::endl
49 << "}" << std::endl;
50 return output;
51 }
52 };
53
54} // frame_transformer
Stuct containing the algorithm configuration values for frame_transformer.
int timeout
Timeout in ms for transform lookup. A value of 0 means lookup will occur once without blocking if it ...
std::string target_frame
The target coordinate frame id to transform data into.
friend std::ostream & operator<<(std::ostream &output, const Config &c)
int queue_size
Queue size for publishers and subscribers.
std::string message_type
Message type which will be transformed.