Skip to content

Commit

Permalink
remove c-style casts
Browse files Browse the repository at this point in the history
  • Loading branch information
jazonshou committed Nov 5, 2024
1 parent d0c3ad0 commit 1c250c7
Show file tree
Hide file tree
Showing 4 changed files with 24 additions and 24 deletions.
2 changes: 1 addition & 1 deletion src/TunePID.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ int main(int argc, char** argv) {

time_point<steady_clock> tp = steady_clock::now();
time_point<steady_clock> startTime = tp;
while (steady_clock::now() - startTime < 3 * milliseconds((int)(period * 1000))) {
while (steady_clock::now() - startTime < 3 * milliseconds(static_cast<int>(period * 1000))) {
int32_t current_angle = can::motor::getMotorPosition(serial).getData();
double difference = (current_angle - angle_target) / 1000.0;
acc_error += difference * difference;
Expand Down
12 changes: 6 additions & 6 deletions src/ar/ARTester.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ int main(int argc, char* argv[]) {
if (!cam_config[cam::KEY_FILENAME].empty() && !parser.has("fo")) {
cam_file = (std::string)cam_config[cam::KEY_FILENAME];
} else if (!cam_config[cam::KEY_CAMERA_ID].empty() && !parser.has("co")) {
cam_id = (int)cam_config[cam::KEY_CAMERA_ID];
cam_id = static_cast<int>(cam_config[cam::KEY_CAMERA_ID]);
} else if (!parser.has("fo") && !parser.has("co")) {
std::cerr << "Error: no file or camera_id was provided in the configuration file or "
"on the command line!"
Expand Down Expand Up @@ -196,8 +196,8 @@ int main(int argc, char* argv[]) {
if (show_grid) {
std::vector<cv::Point2f> grid = projectGrid(imageSize, grid_spacing);
for (cv::Point2f pt : grid) {
cv::Point2f newPt(pt.x * (float)imageSize.width,
pt.y * (float)imageSize.height);
cv::Point2f newPt(pt.x * static_cast<float>(imageSize.width),
pt.y * static_cast<float>(imageSize.height));
cv::drawMarker(frame, newPt, cv::Scalar(255, 0, 0), cv::MARKER_CROSS, 10, 1);
}
}
Expand Down Expand Up @@ -252,14 +252,14 @@ std::vector<cv::Point2d> projectCube(float len, cv::Vec3d rvec, cv::Vec3d tvec)
}

std::vector<cv::Point2f> projectGrid(cv::Size imageSize, int spacing) {
cv::Point2f center((float)imageSize.width / 2.0f, (float)imageSize.height / 2.0f);
cv::Point2f center(static_cast<float>(imageSize.width) / 2.0f, static_cast<float>(imageSize.height) / 2.0f);
std::vector<cv::Point2f> grid_points;
std::vector<cv::Point2f> projected_points;
float xf, yf;
for (int x = 0; x < imageSize.width / 2; x += spacing) {
for (int y = 0; y < imageSize.height / 2; y += spacing) {
xf = (float)x;
yf = (float)y;
xf = static_cast<float>(x);
yf = static_cast<float>(y);
grid_points.push_back(cv::Point2f(xf, yf) + center);
if (x != 0 || y != 0) {
grid_points.push_back(cv::Point2f(-xf, -yf) + center);
Expand Down
4 changes: 2 additions & 2 deletions src/camera/CameraParams.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,8 +93,8 @@ void CameraParams::readFromFileNode(const cv::FileNode& file_node) {
file_node[KEY_CAMERA_MATRIX] >> cam;
file_node[KEY_DIST_COEFFS] >> dist;
int w, h;
w = (int)file_node[KEY_IMAGE_WIDTH];
h = (int)file_node[KEY_IMAGE_HEIGHT];
w = static_cast<int>(file_node[KEY_IMAGE_WIDTH]);
h = static_cast<int>(file_node[KEY_IMAGE_HEIGHT]);
cv::Size size(w, h);
// call init to do validation
init(cam, dist, size);
Expand Down
30 changes: 15 additions & 15 deletions src/camera/calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,12 +135,12 @@ computeReprojectionErrors(const std::vector<std::vector<cv::Point3f>>& objectPoi
double totalErr = 0, err;
perViewErrors.resize(objectPoints.size());

for (i = 0; i < (int)objectPoints.size(); i++) {
for (i = 0; i < static_cast<int>(objectPoints.size()); i++) {
projectPoints(cv::Mat(objectPoints[i]), rvecs[i], tvecs[i], cameraMatrix, distCoeffs,
imagePoints2);
err = norm(cv::Mat(imagePoints[i]), cv::Mat(imagePoints2), cv::NORM_L2);
int n = (int)objectPoints[i].size();
perViewErrors[i] = (float)std::sqrt(err * err / n);
int n = static_cast<int>(objectPoints[i].size());
perViewErrors[i] = static_cast<float>(std::sqrt(err * err / n));
totalErr += err * err;
totalPoints += n;
}
Expand Down Expand Up @@ -264,7 +264,7 @@ saveCameraParams(const std::string& filename, cv::Size imageSize, cv::Size board
fs << "per_view_reprojection_errors" << cv::Mat(reprojErrs);

if (!rvecs.empty() || !reprojErrs.empty())
fs << "nframes" << (int)std::max(rvecs.size(), reprojErrs.size());
fs << "nframes" << static_cast<int>(std::max(rvecs.size(), reprojErrs.size()));

if (flags & cv::CALIB_FIX_ASPECT_RATIO)
fs << "aspectRatio" << aspectRatio;
Expand Down Expand Up @@ -293,8 +293,8 @@ saveCameraParams(const std::string& filename, cv::Size imageSize, cv::Size board

if (!rvecs.empty() && !tvecs.empty()) {
CV_Assert(rvecs[0].type() == tvecs[0].type());
cv::Mat bigmat((int)rvecs.size(), 6, rvecs[0].type());
for (int i = 0; i < (int)rvecs.size(); i++) {
cv::Mat bigmat(static_cast<int>(rvecs.size()), 6, rvecs[0].type());
for (int i = 0; i < static_cast<int>(rvecs.size()); i++) {
cv::Mat r = bigmat(cv::Range(i, i + 1), cv::Range(0, 3));
cv::Mat t = bigmat(cv::Range(i, i + 1), cv::Range(3, 6));

Expand All @@ -310,8 +310,8 @@ saveCameraParams(const std::string& filename, cv::Size imageSize, cv::Size board
}

if (!imagePoints.empty()) {
cv::Mat imagePtMat((int)imagePoints.size(), (int)imagePoints[0].size(), CV_32FC2);
for (int i = 0; i < (int)imagePoints.size(); i++) {
cv::Mat imagePtMat(static_cast<int>(imagePoints.size()), static_cast<int>(imagePoints[0].size()), CV_32FC2);
for (int i = 0; i < static_cast<int>(imagePoints.size()); i++) {
cv::Mat r = imagePtMat.row(i).reshape(2, imagePtMat.cols);
cv::Mat imgpti(imagePoints[i]);
imgpti.copyTo(r);
Expand Down Expand Up @@ -489,7 +489,7 @@ int main(int argc, char** argv) {
return fprintf(stderr, "Could not initialize video (%d) capture\n", cameraId), -2;

if (!imageList.empty())
nframes = (int)imageList.size();
nframes = static_cast<int>(imageList.size());

if (capture.isOpened())
printf("%s", liveCaptureHelp);
Expand All @@ -509,7 +509,7 @@ int main(int argc, char** argv) {
cv::Mat view0;
capture >> view0;
view0.copyTo(view);
} else if (i < (int)imageList.size())
} else if (i < static_cast<int>(imageList.size()))
view = cv::imread(imageList[i], 1);

if (view.empty()) {
Expand Down Expand Up @@ -573,9 +573,9 @@ int main(int argc, char** argv) {

if (mode == CAPTURING) {
if (undistortImage)
msg = cv::format("%d/%d Undist", (int)imagePoints.size(), nframes);
msg = cv::format("%d/%d Undist", static_cast<int>(imagePoints.size()), nframes);
else
msg = cv::format("%d/%d", (int)imagePoints.size(), nframes);
msg = cv::format("%d/%d", static_cast<int>(imagePoints.size()), nframes);
}

putText(view, msg, textOrigin, 1, 1,
Expand All @@ -590,7 +590,7 @@ int main(int argc, char** argv) {
}

imshow("Image View", view);
char key = (char)cv::waitKey(capture.isOpened() ? 50 : 500);
char key = static_cast<char>(cv::waitKey(capture.isOpened() ? 50 : 500));

if (key == 27)
break;
Expand Down Expand Up @@ -622,14 +622,14 @@ int main(int argc, char** argv) {
getOptimalNewCameraMatrix(cameraMatrix, distCoeffs, imageSize, 1, imageSize, 0),
imageSize, CV_16SC2, map1, map2);

for (i = 0; i < (int)imageList.size(); i++) {
for (i = 0; i < static_cast<int>(imageList.size()); i++) {
view = cv::imread(imageList[i], 1);
if (view.empty())
continue;
// undistort( view, rview, cameraMatrix, distCoeffs, cameraMatrix );
remap(view, rview, map1, map2, cv::INTER_LINEAR);
imshow("Image View", rview);
char c = (char)cv::waitKey();
char c = static_cast<char>(cv::waitKey());
if (c == 27 || c == 'q' || c == 'Q')
break;
}
Expand Down

0 comments on commit 1c250c7

Please sign in to comment.