24 namespace perception {
43 inline const std::set<std::string> &
vertices() {
return vertices_; }
45 bool Init(
const std::vector<std::string> &camera_names,
46 const std::string ¶ms_path);
48 bool AddTransform(
const std::string &child_frame_id,
49 const std::string &frame_id,
50 const Eigen::Affine3d &transform);
52 bool QueryTransform(
const std::string &child_frame_id,
53 const std::string &frame_id, Eigen::Affine3d *transform);
57 bool LoadFromFile(
const std::string &tf_input,
float frequency = 200.0f);
59 bool QueryPos(
double timestamp, Eigen::Affine3d *pose);
63 std::string child_frame_id;
65 Eigen::Affine3d transform;
68 std::vector<Transform> tf_;
70 double error_limit_ = 1.0;
72 std::set<std::string> vertices_;
75 std::multimap<std::string, Edge> edges_;
77 bool FindTransform(
const std::string &child_frame_id,
78 const std::string &frame_id, Eigen::Affine3d *transform,
79 std::map<std::string, bool> *visited);