$darkmode
osi_omni_sensor.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2020 Robert Bosch GmbH
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of 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,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16  * SPDX-License-Identifier: Apache-2.0
17  */
23 #pragma once
24 
25 #include <map> // for map<>
26 #include <memory> // for shared_ptr<>, unique_ptr<>
27 #include <string> // for string
28 #include <utility> // for move
29 
30 #include <Eigen/Geometry> // for Isometry3d, Vector3d
31 
32 #include <cloe/component/lane_boundary.hpp> // for LaneBoundary
33 #include <cloe/component/object.hpp> // for Object
34 #include <cloe/core.hpp> // for Json, Duration
35 #include <cloe/simulator.hpp> // for ModelError
36 #include <cloe/sync.hpp> // for Sync
37 
38 #include "osi_common.pb.h" // for Timestamp, Identifier, BaseMoving, ..
39 #include "osi_detectedobject.pb.h" // for DetectedMovingObject
40 #include "osi_hostvehicledata.pb.h" // for HostVehicleData
41 #include "osi_object.pb.h" // for MovingObject
42 #include "osi_sensordata.pb.h" // for SensorData, DetectedEntityHeader
43 
44 #include "osi_ground_truth.hpp" // for OsiGroundTruth
45 #include "osi_transceiver.hpp" // for OsiTransceiver
46 #include "osi_utils.hpp"
47 
48 namespace osii {
49 
53 cloe::Duration osi_timestamp_to_time(const osi3::Timestamp& timestamp);
54 
55 void from_osi_identifier(const osi3::Identifier& osi_id, int& id);
56 
61 void from_osi_host_vehicle_data(const osi3::HostVehicleData& osi_hv, cloe::Object& obj);
62 
68 void from_osi_base_moving(const osi3::BaseMoving& osi_bm, cloe::Object& obj);
69 
74 void from_osi_base_moving_alt(const osi3::BaseMoving& osi_bm,
75  const osi3::BaseMoving& osi_bm_gt,
76  cloe::Object& obj);
77 
78 template <typename T>
79 void from_osi_mov_obj_type_classification(const T& osi_mo, cloe::Object::Class& oc);
80 void from_osi_mov_obj_type_classification(
81  const osi3::MovingObject::Type& osi_ot,
82  const osi3::MovingObject::VehicleClassification::Type& osi_vt,
83  cloe::Object::Class& oc);
84 
85 void from_osi_detected_moving_object_alt(const osi3::DetectedMovingObject& osi_mo,
86  const OsiGroundTruth& ground_truth, cloe::Object& obj);
87 
88 void from_osi_boundary_points(const osi3::LaneBoundary& osi_lb, cloe::LaneBoundary& lb);
89 
90 void transform_ego_coord_from_osi_data(const Eigen::Vector3d& dimensions_gt, cloe::Object& obj);
91 
98 void transform_obj_coord_from_osi_data(const Eigen::Isometry3d& sensor_pose,
99  const Eigen::Vector3d& dimensions_gt,
100  cloe::Object& obj);
101 
102 Eigen::Isometry3d osi_position_orientation_to_pose_alt(const osi3::BaseMoving& base,
103  const osi3::BaseMoving& base_gt);
104 
106  const osi3::MovingObject::VehicleAttributes& osi_va);
107 
112 enum class SensorMockTarget { MountingPosition, DetectedMovingObject, DetectedLaneBoundary };
113 
121 enum class SensorMockLevel { OverwriteNone, InterpolateMissing, OverwriteAll };
122 
123 // clang-format off
124 ENUM_SERIALIZATION(SensorMockLevel, ({
125  {SensorMockLevel::OverwriteNone, "overwrite_none"},
126  {SensorMockLevel::InterpolateMissing, "interpolate_missing"},
127  {SensorMockLevel::OverwriteAll, "overwrite_all"},
128 }))
129 // clang-format on
130 
131 
134 struct SensorMockConf : public cloe::Confable {
135  using Target = SensorMockTarget;
136  using Level = SensorMockLevel;
137 
138  SensorMockConf() = default;
139 
140  virtual ~SensorMockConf() noexcept = default;
141 
142  std::map<Target, Level> level = {{Target::MountingPosition, Level::OverwriteNone},
143  {Target::DetectedMovingObject, Level::OverwriteNone},
144  {Target::DetectedLaneBoundary, Level::OverwriteNone}};
145 
146  CONFABLE_SCHEMA(SensorMockConf) {
147  return fable::Schema{
148  // clang-format off
149  {"mounting_position", cloe::Schema(&level[Target::MountingPosition], "mock level for sensor mounting position")},
150  {"detected_moving_objects", cloe::Schema(&level[Target::DetectedMovingObject], "mock level for detected moving objects")},
151  {"detected_lane_boundaries", cloe::Schema(&level[Target::DetectedLaneBoundary], "mock level for detected lane boundaries")},
152  // clang-format on
153  };
154  }
155 
156  void to_json(cloe::Json& j) const override {
157  j["mounting_position"] = level.at(SensorMockTarget::MountingPosition);
158  j["detected_moving_objects"] = level.at(SensorMockTarget::DetectedMovingObject);
159  j["detected_lane_boundaries"] = level.at(SensorMockTarget::DetectedLaneBoundary);
160  }
161 };
162 
167  public:
168  virtual ~OsiOmniSensor() = default;
169  OsiOmniSensor() = delete;
170 
174  OsiOmniSensor(std::unique_ptr<OsiTransceiver>&& osi_transceiver, uint64_t owner_id)
175  : osi_comm_(std::move(osi_transceiver)), owner_id_(owner_id) {
176  ground_truth_ = std::make_unique<OsiGroundTruth>();
177  }
178 
185  OsiOmniSensor(OsiTransceiver* osi_transceiver, uint64_t owner_id)
186  : osi_comm_(osi_transceiver), owner_id_(owner_id) {
187  ground_truth_ = std::make_unique<OsiGroundTruth>();
188  }
189 
193  virtual void step(const cloe::Sync& s, const bool& restart, cloe::Duration& sim_time);
194 
199  virtual void process(const osi3::Timestamp& timestamp);
200 
207  virtual void process(osi3::SensorData* osi_sd, cloe::Duration& sim_time);
208 
214  virtual void process(const osi3::SensorView& osi_sv);
215 
222  virtual void process(const bool has_veh_data,
223  const osi3::HostVehicleData& osi_hv,
224  const osi3::MovingObject& osi_ego);
225 
232  virtual void process(const bool has_eh,
233  const osi3::DetectedEntityHeader& osi_eh,
234  const osi3::DetectedMovingObject& osi_mo);
235 
236  void mock_detected_lane_boundaries();
237 
238  void from_osi_boundary_points(const osi3::LaneBoundary& osi_lb, cloe::LaneBoundary& lb);
239 
245  virtual void store_ego_object(std::shared_ptr<cloe::Object> ego_obj) = 0;
246 
252  virtual void store_object(std::shared_ptr<cloe::Object> obj) = 0;
253 
259  virtual void store_lane_boundary(const cloe::LaneBoundary& lb) = 0;
260 
264  virtual void store_sensor_meta_data(const Eigen::Vector3d& bbcenter_to_veh_origin,
265  const Eigen::Vector3d& ego_dimensions) = 0;
266 
270  cloe::Duration osi_timestamp_to_simtime(const osi3::Timestamp& timestamp) const;
271 
275  virtual Eigen::Isometry3d get_static_mounting_position(
276  const Eigen::Vector3d& bbcenter_to_veh_origin, const Eigen::Vector3d& ego_dimensions) = 0;
277 
278  virtual void set_mock_conf(std::shared_ptr<const SensorMockConf> mock) = 0;
279 
280  SensorMockLevel get_mock_level(SensorMockTarget trg_type) const {
281  return mock_->level.at(trg_type);
282  }
283 
284  friend void to_json(cloe::Json& j, const OsiOmniSensor& c) {
285  j = cloe::Json{
286  {"osi_connection", *c.osi_comm_},
287  };
288  }
289 
290  protected:
293  std::unique_ptr<OsiTransceiver> osi_comm_;
294 
296  std::unique_ptr<OsiGroundTruth> ground_truth_;
297 
299  uint64_t owner_id_;
300 
302  Eigen::Isometry3d osi_ego_pose_;
303 
305  Eigen::Isometry3d osi_sensor_pose_;
306 
309 
311  std::shared_ptr<const SensorMockConf> mock_{nullptr};
312 };
313 } // namespace osii
Definition: lane_boundary.hpp:36
Definition: sync.hpp:34
Definition: schema.hpp:175
Definition: osi_omni_sensor.hpp:166
std::unique_ptr< OsiGroundTruth > ground_truth_
Access to osi ground truth, e.g. for mock-ups.
Definition: osi_omni_sensor.hpp:296
OsiOmniSensor(std::unique_ptr< OsiTransceiver > &&osi_transceiver, uint64_t owner_id)
Definition: osi_omni_sensor.hpp:174
Eigen::Isometry3d osi_ego_pose_
Store ego pose (reference point is rear axle center, not ground level).
Definition: osi_omni_sensor.hpp:302
virtual void store_sensor_meta_data(const Eigen::Vector3d &bbcenter_to_veh_origin, const Eigen::Vector3d &ego_dimensions)=0
cloe::Duration osi_timestamp_to_simtime(const osi3::Timestamp &timestamp) const
Definition: osi_omni_sensor.cpp:150
virtual void store_ego_object(std::shared_ptr< cloe::Object > ego_obj)=0
virtual Eigen::Isometry3d get_static_mounting_position(const Eigen::Vector3d &bbcenter_to_veh_origin, const Eigen::Vector3d &ego_dimensions)=0
OsiOmniSensor(OsiTransceiver *osi_transceiver, uint64_t owner_id)
Definition: osi_omni_sensor.hpp:185
std::unique_ptr< OsiTransceiver > osi_comm_
Definition: osi_omni_sensor.hpp:293
uint64_t owner_id_
Id of the sensor's owner (ego).
Definition: osi_omni_sensor.hpp:299
virtual void store_lane_boundary(const cloe::LaneBoundary &lb)=0
virtual void process(const osi3::Timestamp &timestamp)
Definition: osi_omni_sensor.cpp:382
virtual void store_object(std::shared_ptr< cloe::Object > obj)=0
cloe::Duration init_time_
Initial simulation time.
Definition: osi_omni_sensor.hpp:308
Eigen::Isometry3d osi_sensor_pose_
Store sensor pose relative to the ego frame (rear axle center, not ground level).
Definition: osi_omni_sensor.hpp:305
std::shared_ptr< const SensorMockConf > mock_
Use alternative source for required data or overwrite incoming data, if requested.
Definition: osi_omni_sensor.hpp:311
virtual void step(const cloe::Sync &s, const bool &restart, cloe::Duration &sim_time)
Definition: osi_omni_sensor.cpp:355
Definition: osi_transceiver.hpp:50
std::chrono::nanoseconds Duration
Definition: cloe_fwd.hpp:36
#define ENUM_SERIALIZATION(xType, xMap)
Definition: enum.hpp:51
void from_osi_base_moving(const osi3::BaseMoving &osi_bm, cloe::Object &obj)
Definition: osi_omni_sensor.cpp:226
void from_osi_base_moving_alt(const osi3::BaseMoving &osi_bm, const osi3::BaseMoving &osi_bm_gt, cloe::Object &obj)
Definition: osi_omni_sensor.cpp:244
void transform_obj_coord_from_osi_data(const Eigen::Isometry3d &sensor_pose, const Eigen::Vector3d &dimensions_gt, cloe::Object &obj)
Definition: osi_omni_sensor.cpp:325
void from_osi_host_vehicle_data(const osi3::HostVehicleData &osi_hv, cloe::Object &obj)
Definition: osi_omni_sensor.cpp:158
cloe::Duration osi_timestamp_to_time(const osi3::Timestamp &timestamp)
Definition: osi_omni_sensor.cpp:145
SensorMockTarget
Definition: osi_omni_sensor.hpp:112
Eigen::Vector3d osi_vehicle_attrib_rear_offset_to_vector3d(const osi3::MovingObject::VehicleAttributes &osi_va)
Definition: osi_utils.cpp:77
SensorMockLevel
Definition: osi_omni_sensor.hpp:121
Definition: object.hpp:51