23 #include "Eigen/Dense" 24 #include "gflags/gflags.h" 29 namespace perception {
52 double max_duration = 0.0);
59 double cache_duration_ = 1.0;
67 void Init(
const std::string& sensor2novatel_tf2_child_frame_id);
68 void Init(
const std::string& sensor2novatel_tf2_frame_id,
69 const std::string& sensor2novatel_tf2_child_frame_id,
70 const std::string& novatel2world_tf2_frame_id,
71 const std::string& novatel2world_tf2_child_frame_id);
74 bool GetSensor2worldTrans(
double timestamp,
82 const std::string& frame_id,
const std::string& child_frame_id);
84 bool GetExtrinsicsBySensorId(
const std::string& from_sensor_id,
85 const std::string& to_sensor_id,
90 const std::string& frame_id,
91 const std::string& child_frame_id);
98 std::string sensor2novatel_tf2_frame_id_;
99 std::string sensor2novatel_tf2_child_frame_id_;
100 std::string novatel2world_tf2_frame_id_;
101 std::string novatel2world_tf2_child_frame_id_;
103 std::unique_ptr<Eigen::Affine3d> sensor2novatel_extrinsics_;
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
DECLARE_double(obs_buffer_match_precision)
DECLARE_string(obs_screen_output_dir)
bool Init(const char *binary_name)
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34