Commit 7a2ac925 authored by James Ward's avatar James Ward
Browse files

Remove unused struct member

parent 2cf8c8fc
......@@ -16,7 +16,6 @@ struct initial_parameters_t
cv::Size board_dimensions; // in millimetres
cv::Point3d cb_translation_error; // in millimetres
cv::Mat cameramat;
int distcoeff_num;
cv::Mat distcoeff;
std::pair<int, int> image_size; // in pixels
};
......
......@@ -21,47 +21,10 @@ void loadParams(const ros::NodeHandle& n, initial_parameters_t& i_params)
cv::Mat(3, 3, CV_64F, camera_mat.data()).copyTo(i_params.cameramat);
std::vector<double> dist_coeff;
n.getParam("distcoeff", dist_coeff);
i_params.distcoeff_num = dist_coeff.size();
cv::Mat(1, i_params.distcoeff_num, CV_64F, dist_coeff.data()).copyTo(i_params.distcoeff);
cv::Mat(1, dist_coeff.size(), CV_64F, dist_coeff.data()).copyTo(i_params.distcoeff);
n.getParam("image_size/l", i_l);
n.getParam("image_size/b", i_b);
i_params.image_size = std::make_pair(i_l, i_b);
/*
std::string pkg_loc = ros::package::getPath("cam_lidar_calibration");
std::ifstream infile(pkg_loc + "/cfg/initial_params.txt");
infile >> i_params.camera_topic;
infile >> i_params.lidar_topic;
infile >> i_params.fisheye_model;
infile >> i_params.lidar_ring_count;
infile >> cb_l;
infile >> cb_b;
i_params.grid_size = std::make_pair(cb_l, cb_b);
infile >> i_params.square_length;
infile >> l;
infile >> b;
i_params.board_dimension = std::make_pair(l, b);
infile >> e_l;
infile >> e_b;
i_params.cb_translation_error = std::make_pair(e_l, e_b);
double camera_mat[9];
for (int i = 0; i < 9; i++)
{
infile >> camera_mat[i];
}
cv::Mat(3, 3, CV_64F, &camera_mat).copyTo(i_params.cameramat);
infile >> i_params.distcoeff_num;
double dist_coeff[i_params.distcoeff_num];
for (int i = 0; i < i_params.distcoeff_num; i++)
{
infile >> dist_coeff[i];
}
cv::Mat(1, i_params.distcoeff_num, CV_64F, &dist_coeff).copyTo(i_params.distcoeff);
infile >> i_l;
infile >> i_b;
i_params.image_size = std::make_pair(i_l, i_b);
*/
}
} // namespace cam_lidar_calibration
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment