Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
32 changes: 12 additions & 20 deletions calibrate_sweeps/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,14 +7,23 @@ project(calibrate_sweeps)
find_package(catkin REQUIRED COMPONENTS roscpp message_generation qt_build semantic_map metaroom_xml_parser strands_sweep_registration actionlib actionlib_msgs)

set(CMAKE_CXX_FLAGS "-O4 -fPIC -std=c++0x -fpermissive ${CMAKE_CXX_FLAGS}")
set(CMAKE_PREFIX_PATH /usr/share/pcl-1.7/ ${CMAKE_PREFIX_PATH})
set(PCL_DIR /usr/share/pcl-1.7/)
find_package(PCL 1.7 REQUIRED NO_DEFAULT_PATH)





set(PCL_DIR "/usr/lib/x86_64-linux-gnu/cmake/pcl/")



find_package(PCL 1.3 REQUIRED)

include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})



rosbuild_prepare_qt4(QtCore QtXml)

add_action_files(
Expand All @@ -40,20 +49,3 @@ catkin_package(
include_directories(
${catkin_INCLUDE_DIRS}
)

add_executable(calibrate_sweep_as src/calibrate_sweep_action_server.cpp )
add_dependencies(calibrate_sweep_as calibrate_sweeps_generate_messages_cpp)

target_link_libraries(calibrate_sweep_as
${catkin_LIBRARIES}
${PCL_LIBRARIES}
${QT_LIBRARIES}
)

############################# INSTALL TARGETS

install(TARGETS calibrate_sweep_as
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ pair<int, vector<string> > convex_segment_cloud(int counter, const boost::filesy
map<size_t, size_t> indices;
std::tie(g, convex_g, supervoxels, convex_segments, indices) = ss.compute_convex_oversegmentation(cloud, false);

ss.save_graph(*convex_g, (convex_path / "graph.cereal").string());
//ss.save_graph(*convex_g, (convex_path / "graph.cereal").string());

delete g;
delete convex_g;
Expand Down Expand Up @@ -89,7 +89,7 @@ int main(int argc, char** argv)

summary.index_convex_segment_paths.clear();
int counter = 0;
for (const string& xml : folder_xmls) {
for (const string& xml : folder_xmls) {
vector<string> segment_paths;
tie(counter, segment_paths) = convex_segment_cloud(counter, boost::filesystem::path(xml));
summary.index_convex_segment_paths.insert(summary.index_convex_segment_paths.end(), segment_paths.begin(), segment_paths.end());
Expand Down
Original file line number Diff line number Diff line change
@@ -1,20 +1,59 @@
#include <metaroom_xml_parser/simple_summary_parser.h>
#include <metaroom_xml_parser/simple_xml_parser.h>
#include <metaroom_xml_parser/simple_dynamic_object_parser.h>
#include <metaroom_xml_parser/load_utilities.h>


#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <metaroom_xml_parser/simple_summary_parser.h>
#include <metaroom_xml_parser/simple_xml_parser.h>
#include <metaroom_xml_parser/simple_dynamic_object_parser.h>
#include <metaroom_xml_parser/load_utilities.h>

#include <metaroom_xml_parser/load_utilities.h>

#include "dynamic_object_retrieval/summary_types.h"

using namespace std;
using namespace dynamic_object_retrieval;

using PointT = pcl::PointXYZRGB;

// TODO: shouldn't this be in a header?
void init_folders(const boost::filesystem::path& data_path)
typedef pcl::PointXYZRGB PointType;

typedef pcl::PointXYZRGB PointType;
typedef semantic_map_load_utilties::DynamicObjectData<PointType> ObjectData;

typedef pcl::PointCloud<PointType> Cloud;
typedef typename Cloud::Ptr CloudPtr;

using namespace std;

int main(int argc, char** argv)
{
vector<string> folder_xmls = semantic_map_load_utilties::getSweepXmls<PointT>(data_path.string(), true);
string folder;


if (argc > 1){
folder = argv[1];
} else {
cout<<"Please specify the folder from where to load the data PFE BILAL OUSSAMA."<<endl;
return -1;
}

cout<<"Looking for sweeps..."<<endl;


boost::filesystem::path data_path(argv[1]);

//vector<string> folder_xmls = semantic_map_load_utilties::getSweepXmls<PointT>(data_path.string(),True);
vector<string> folder_xmls = semantic_map_load_utilties::getSweepXmls<PointT>(data_path.string(), true);

cout<<folder_xmls.size()<<" sweeps found."<<endl;




data_summary summary;
summary.nbr_sweeps = folder_xmls.size();

Expand All @@ -36,16 +75,16 @@ void init_folders(const boost::filesystem::path& data_path)
subsegment_summary.save(subsegment_path);
}
}
}

int main(int argc, char** argv)
{
if (argc < 2) {
cout << "Please supply the path containing the sweeps..." << endl;
return 0;
}
for (string sweep : folder_xmls){

init_folders(boost::filesystem::path(argv[1]));
cout<<"Sweep "<<sweep<<endl;

return 0;
vector<ObjectData> objects = semantic_map_load_utilties::loadAllDynamicObjectsFromSingleSweep<PointType>(sweep);
cout<<"Found "<<objects.size()<<" objects"<<endl;
for (size_t k=0; k<objects.size(); k++){
auto object = objects[k];
cout<<"Object "<<k<<" has "<<object.vAdditionalViews.size()<<" additional views"<<endl;
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,15 @@

#include <Eigen/Dense>
#include <Eigen/SVD>
#include "highgui.h"
#include <opencv2/opencv.hpp>

#include <opencv2/opencv.hpp>
#include "opencv2/xfeatures2d.hpp"
#include "opencv2/features2d.hpp"
using namespace std;
using namespace cv;
using namespace cv::xfeatures2d;

using namespace std;

Expand Down Expand Up @@ -123,9 +132,10 @@ void extract_nonoverlapping_sift(SiftCloudT::Ptr& sweep_features, CloudT::Ptr& s
c[0] = cropped_clouds[i]->at(ind).b;
}
}
cv::FastFeatureDetector detector;
Ptr<FastFeatureDetector> detector=FastFeatureDetector::create(10,true);
//cv::FastFeatureDetector detector;
std::vector<cv::KeyPoint> keypoints;
detector.detect(img, keypoints);
detector->detect(img, keypoints);
cv::SIFT::DescriptorParams descriptor_params;
descriptor_params.isNormalize = true; // always true, shouldn't matter
descriptor_params.magnification = 3.0; // 3.0 default
Expand Down Expand Up @@ -277,8 +287,9 @@ tuple<cv::Mat, cv::Mat, int, int> compute_image_for_cloud(CloudT::Ptr& cloud, co
pair<SiftCloudT::Ptr, CloudT::Ptr> extract_sift_features(cv::Mat& image, cv::Mat& depth, int minx, int miny, const Eigen::Matrix3f& K)
{
std::vector<cv::KeyPoint> cv_keypoints;
cv::FastFeatureDetector detector;
detector.detect(image, cv_keypoints);
//cv::FastFeatureDetector detector;
Ptr<FastFeatureDetector>detector=FastFeatureDetector::create(10,true);
detector->detect(image, cv_keypoints);

//-- Step 2: Calculate descriptors (feature vectors)
cv::SIFT::DescriptorParams descriptor_params;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,8 @@ void compute_features(HistCloudT::Ptr& features, CloudT::Ptr& keypoints, CloudT:
for (size_t i = 0; i < pfhrgb_cloud.size(); ++i) {
std::copy(pfhrgb_cloud.at(i).histogram, pfhrgb_cloud.at(i).histogram+N, features->at(i).histogram);
}

std::cout << "Number of features: " << pfhrgb_cloud.size() << std::endl;
}

NormalCloudT::Ptr compute_surfel_normals(SurfelCloudT::Ptr& surfel_cloud, CloudT::Ptr& segment)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,16 @@
#include <pcl/features/normal_3d_omp.h>
#include <pcl/octree/octree.h>

#include "highgui.h"
#include <opencv2/opencv.hpp>

#include <opencv2/opencv.hpp>
#include "opencv2/xfeatures2d.hpp"
#include "opencv2/features2d.hpp"
using namespace std;
using namespace cv;
using namespace cv::xfeatures2d;

#define VISUALIZE false

using namespace std;
Expand Down Expand Up @@ -170,12 +180,12 @@ void register_objects::calculate_features_for_image(cv::Mat& descriptors, std::v
//detector_params.edgeThreshold = 15.0; // 10.0 default
//detector_params.threshold = 0.04; // 0.04 default
//cv::SiftFeatureDetector detector(detector_params);
cv::FastFeatureDetector detector;
Ptr<FastFeatureDetector> detector = FastFeatureDetector::create(10, true);

//cv::StarFeatureDetector detector;
//cv::MserFeatureDetector detector;
detector.detect(image, keypoints);

//detector.detect(image, keypoints);
detector->detect(image, keypoints);
//-- Step 2: Calculate descriptors (feature vectors)
//cv::Mat descriptors;
// the length of the descriptors is 128
Expand Down