23 namespace perception {
27 const std::string& cloud_type =
"xyzit");
34 const std::set<std::string>& black_list,
35 std::vector<ObjectPtr>* objects_out,
36 std::vector<PointCloud>* left_boundary =
nullptr,
37 std::vector<PointCloud>* right_boundary =
nullptr,
38 std::vector<PointCloud>* road_polygon =
nullptr,
39 std::vector<PointCloud>* left_lane_boundary =
nullptr,
40 std::vector<PointCloud>* right_lane_boundary =
nullptr,
47 const std::vector<ObjectPtr>& objects,
48 const int frame_id = 0);
bool save_frame_objects(const std::string &filename, const std::vector< ObjectPtr > &objects, const int frame_id=0)
bool load_pcl_pcds_xyzl(const std::string &filename, PointCloudPtr cloud_out)
bool load_sensor2world_pose(const std::string &filename, Eigen::Matrix4d *pose_out)
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: pointcloud.h:26
Eigen::Matrix4d Matrix4d
Definition: base_map_fwd.h:32
pcl::PointCloud< Point >::Ptr PointCloudPtr
Definition: types.h:65
bool load_pcl_pcds(const std::string &filename, PointCloudPtr cloud_out, const std::string &cloud_type="xyzit")
bool load_pcl_pcds_xyzit(const std::string &filename, PointCloudPtr cloud_out)
bool load_frame_objects(const std::string &filename, const std::set< std::string > &black_list, std::vector< ObjectPtr > *objects_out, std::vector< PointCloud > *left_boundary=nullptr, std::vector< PointCloud > *right_boundary=nullptr, std::vector< PointCloud > *road_polygon=nullptr, std::vector< PointCloud > *left_lane_boundary=nullptr, std::vector< PointCloud > *right_lane_boundary=nullptr, PointCloud *cloud=nullptr)