49 : tf_child_frame_id_(
""),
50 radar_forward_distance_(200.0),
51 odometry_channel_name_(
""),
52 hdmap_input_(nullptr),
53 radar_preprocessor_(nullptr),
54 radar_perception_(nullptr) {}
58 bool Proc(
const std::shared_ptr<drivers::OculiiPointCloud>& message)
override;
63 const std::shared_ptr<const drivers::OculiiPointCloud>& in_message,
64 std::shared_ptr<onboard::SensorFrameMessage> out_message);
65 bool GetCarLocalizationSpeed(
double timestamp,
66 Eigen::Vector3f* car_linear_speed,
67 Eigen::Vector3f* car_angular_speed);
75 static std::atomic<uint32_t> seq_num_;
78 std::string tf_child_frame_id_;
79 double radar_forward_distance_;
80 std::string odometry_channel_name_;
85 std::shared_ptr<BasePreprocessor> radar_preprocessor_;
86 std::shared_ptr<BaseRadarObstaclePerception> radar_perception_;
88 std::shared_ptr<apollo::cyber::Writer<onboard::SensorFrameMessage>> writer_;