Skip to content

Commit

Permalink
Merge branch 'develop'
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Feb 11, 2024
2 parents 8af862c + 5a6c708 commit 5c35862
Show file tree
Hide file tree
Showing 12 changed files with 74 additions and 33 deletions.
47 changes: 30 additions & 17 deletions apps/kinect-stereo-calib/kinect_calibrate_guiMain.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -780,7 +780,7 @@ kinect_calibrate_guiDialog::kinect_calibrate_guiDialog(
cbOptK3 = new wxCheckBox(
Panel12, ID_CHECKBOX6, _("k3 (r^6 dist.)"), wxDefaultPosition,
wxDefaultSize, 0, wxDefaultValidator, _T("ID_CHECKBOX6"));
cbOptK3->SetValue(false);
cbOptK3->SetValue(true);
FlexGridSizer35->Add(
cbOptK3, 1, wxALL | wxALIGN_LEFT | wxALIGN_CENTER_VERTICAL, 1);
FlexGridSizer35->Add(
Expand All @@ -789,13 +789,13 @@ kinect_calibrate_guiDialog::kinect_calibrate_guiDialog(
cbOptT1 = new wxCheckBox(
Panel12, ID_CHECKBOX7, _("t1 (tang. dist.)"), wxDefaultPosition,
wxDefaultSize, 0, wxDefaultValidator, _T("ID_CHECKBOX7"));
cbOptT1->SetValue(false);
cbOptT1->SetValue(true);
FlexGridSizer35->Add(
cbOptT1, 1, wxALL | wxALIGN_LEFT | wxALIGN_CENTER_VERTICAL, 1);
cbOptT2 = new wxCheckBox(
Panel12, ID_CHECKBOX8, _("t2 (tang. dist.)"), wxDefaultPosition,
wxDefaultSize, 0, wxDefaultValidator, _T("ID_CHECKBOX8"));
cbOptT2->SetValue(false);
cbOptT2->SetValue(true);
FlexGridSizer35->Add(
cbOptT2, 1, wxALL | wxALIGN_LEFT | wxALIGN_CENTER_VERTICAL, 1);
Panel12->SetSizer(FlexGridSizer35);
Expand Down Expand Up @@ -826,7 +826,7 @@ kinect_calibrate_guiDialog::kinect_calibrate_guiDialog(
Panel13, ID_CHECKBOX3, _("Pseudo-Huber robust kernel"),
wxDefaultPosition, wxDefaultSize, 0, wxDefaultValidator,
_T("ID_CHECKBOX3"));
cbCalibUseRobust->SetValue(false);
cbCalibUseRobust->SetValue(true);
FlexGridSizer34->Add(
cbCalibUseRobust, 1,
wxALL | wxALIGN_CENTER_HORIZONTAL | wxALIGN_CENTER_VERTICAL, 5);
Expand Down Expand Up @@ -1752,28 +1752,34 @@ void kinect_calibrate_guiDialog::ProcessNewSelectedImageListBox()
{
try
{
static std::optional<mrpt::img::CImage> noImg;
if (!noImg)
{
noImg.emplace(320, 240, CH_RGB);
noImg->filledRectangle(0, 0, 319, 239, TColor(200, 200, 200));
noImg->textOut(100, 110, "(No image selected)", TColor::white());
}

const int sel = lbImagePairs->GetSelection();

if (sel == wxNOT_FOUND || sel >= (int)m_calib_images.size())
{
mrpt::img::CImage img(320, 240, CH_RGB);
img.filledRectangle(0, 0, 319, 239, TColor(200, 200, 200));
img.textOut(100, 110, "(No image selected)", TColor::white());

this->m_view_left->AssignImage(img);
this->m_view_right->AssignImage(img);
this->m_view_left->AssignImage(*noImg);
this->m_view_right->AssignImage(*noImg);
}
else
{
const int image_mode = rbShowImages->GetSelection();

CImage il, ir;

const auto& selPair = m_calib_images[sel];

// Common part to all (but one) modes:
if (image_mode != 1)
{
il = m_calib_images[sel].left.img_original;
ir = m_calib_images[sel].right.img_original;
il = selPair.left.img_original;
ir = selPair.right.img_original;

if (cbCalibNormalize->IsChecked())
{
Expand All @@ -1792,8 +1798,15 @@ void kinect_calibrate_guiDialog::ProcessNewSelectedImageListBox()
// ======= Detected chessboard =======
case 1:
{
il = m_calib_images[sel].left.img_checkboard;
ir = m_calib_images[sel].right.img_checkboard;
if (!selPair.left.img_checkboard.isEmpty())
il = selPair.left.img_checkboard;
else
il = *noImg;

if (!selPair.right.img_checkboard.isEmpty())
ir = selPair.right.img_checkboard;
else
ir = *noImg;
}
break;

Expand All @@ -1804,11 +1817,11 @@ void kinect_calibrate_guiDialog::ProcessNewSelectedImageListBox()
ir = ir.colorImage();

il.drawChessboardCorners(
m_calib_images[sel].left.projectedPoints_distorted,
selPair.left.projectedPoints_distorted,
m_calib_params.check_size_x,
m_calib_params.check_size_y);
ir.drawChessboardCorners(
m_calib_images[sel].right.projectedPoints_distorted,
selPair.right.projectedPoints_distorted,
m_calib_params.check_size_x,
m_calib_params.check_size_y);
}
Expand Down Expand Up @@ -2133,7 +2146,7 @@ void kinect_calibrate_guiDialog::OnbtnSaveCalibClick(wxCommandEvent& event)
c["right_camera_pose"] =
m_calib_result.cam_params.rightCameraPose.asString();

auto& r = c["calibration_results"] = mrpt::containers::yaml::Map();
auto r = c["calibration_results"] = mrpt::containers::yaml::Map();
r["iters"] = m_calib_result.final_iters;
r["good_image_pairs"] = m_calib_result.final_number_good_image_pairs;
r["final_rmse"] = m_calib_result.final_rmse;
Expand Down
2 changes: 1 addition & 1 deletion appveyor.yml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# version format
version: 2.11.8-{branch}-build{build}
version: 2.11.9-{branch}-build{build}

os: Visual Studio 2019

Expand Down
12 changes: 12 additions & 0 deletions doc/source/doxygen-docs/changelog.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,17 @@
\page changelog Change Log

# Version 2.11.9: Released Feb 11th, 2024
- Changes in libraries:
- \ref mrpt_vision_grp:
- mrpt::vision::TStereoCalibParams::use_robust_kernel now defaults to `true`.
- \ref mrpt_img_grp:
- Fix const-correctness of arguments in mrpt::img::CImage::drawChessboardCorners()
- \ref mrpt_obs_grp:
- Added support for mrpt::typemeta::TEnumType to mrpt::obs::CActionRobotMovement3D::TDrawSampleMotionModel and mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel.
- BUG FIXES:
- Fix missing build dep on tf2_geometry_msgs for ROS 1 only.
- Application kinect-stereo-calib: fix exceptions when selecting images without a good chessboard detection on the left list box.

# Version 2.11.8: Released Feb 7th, 2024
- Changes in apps:
- RawLogViewer: Show pointcloud ring, intensity, and time min/max ranges.
Expand Down
6 changes: 3 additions & 3 deletions libs/img/include/mrpt/img/CImage.h
Original file line number Diff line number Diff line change
Expand Up @@ -445,9 +445,9 @@ class CImage : public mrpt::serialization::CSerializable, public CCanvas
* \sa mrpt::vision::findChessboardCorners
*/
bool drawChessboardCorners(
std::vector<TPixelCoordf>& cornerCoords, unsigned int check_size_x,
unsigned int check_size_y, unsigned int lines_width = 1,
unsigned int circles_radius = 4);
const std::vector<TPixelCoordf>& cornerCoords,
unsigned int check_size_x, unsigned int check_size_y,
unsigned int lines_width = 1, unsigned int circles_radius = 4);

/** Joins two images side-by-side horizontally. Both images must have the
* same number of rows and be of the same type (i.e. depth and color mode)
Expand Down
2 changes: 1 addition & 1 deletion libs/img/src/CImage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1847,7 +1847,7 @@ void CImage::rotateImage(
}

bool CImage::drawChessboardCorners(
std::vector<TPixelCoordf>& cornerCoords, unsigned int check_size_x,
const std::vector<TPixelCoordf>& cornerCoords, unsigned int check_size_x,
unsigned int check_size_y, unsigned int lines_width, unsigned int r)
{
#if MRPT_HAS_OPENCV
Expand Down
5 changes: 5 additions & 0 deletions libs/obs/include/mrpt/obs/CActionRobotMovement2D.h
Original file line number Diff line number Diff line change
Expand Up @@ -247,3 +247,8 @@ MRPT_ENUM_TYPE_BEGIN(mrpt::obs::CActionRobotMovement2D::TEstimationMethod)
MRPT_FILL_ENUM_MEMBER(mrpt::obs::CActionRobotMovement2D, emOdometry);
MRPT_FILL_ENUM_MEMBER(mrpt::obs::CActionRobotMovement2D, emScan2DMatching);
MRPT_ENUM_TYPE_END()

MRPT_ENUM_TYPE_BEGIN(mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel)
MRPT_FILL_ENUM_MEMBER(mrpt::obs::CActionRobotMovement2D, mmGaussian);
MRPT_FILL_ENUM_MEMBER(mrpt::obs::CActionRobotMovement2D, mmThrun);
MRPT_ENUM_TYPE_END()
6 changes: 6 additions & 0 deletions libs/obs/include/mrpt/obs/CActionRobotMovement3D.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

#include <mrpt/obs/CAction.h>
#include <mrpt/poses/CPose3DPDFGaussian.h>
#include <mrpt/typemeta/TEnumType.h>

namespace mrpt::obs
{
Expand Down Expand Up @@ -125,3 +126,8 @@ class CActionRobotMovement3D : public CAction
}; // End of class def.

} // namespace mrpt::obs

MRPT_ENUM_TYPE_BEGIN(mrpt::obs::CActionRobotMovement3D::TDrawSampleMotionModel)
MRPT_FILL_ENUM_MEMBER(mrpt::obs::CActionRobotMovement3D, mmGaussian);
MRPT_FILL_ENUM_MEMBER(mrpt::obs::CActionRobotMovement3D, mm6DOF);
MRPT_ENUM_TYPE_END()
5 changes: 4 additions & 1 deletion libs/obs/src/CSimpleMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@
#include <mrpt/serialization/metaprogramming_serialization.h>
#include <mrpt/serialization/optional_serialization.h>

#include <iostream>

using namespace mrpt::obs;
using namespace mrpt::maps;
using namespace mrpt::poses;
Expand Down Expand Up @@ -131,8 +133,9 @@ bool CSimpleMap::loadFromFile(const std::string& filName)
archiveFrom(fi) >> *this;
return true;
}
catch (...)
catch (const std::exception& e)
{
std::cerr << "[CSimpleMap::loadFromFile]" << e.what() << std::endl;
return false;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -80,11 +80,11 @@ struct TStereoCalibParams
bool optimize_k1{true}, optimize_k2{true}, optimize_k3{false},
optimize_t1{false}, optimize_t2{false};

/** Employ a Pseudo-Huber robustifier kernel (Default: false) */
bool use_robust_kernel{false};
/** Employ a Pseudo-Huber robustifier kernel (Default: true) */
bool use_robust_kernel = true;
/** The parameter of the robust kernel, in pixels (only if
* use_robust_kernel=true) (Default=10) */
double robust_kernel_param{10};
* use_robust_kernel=true) (Default=5) */
double robust_kernel_param = 5;

/** If set to !=NULL, this function will be called within each Lev-Marq.
* iteration (don't do heavy stuff here since performance will degrade) */
Expand Down
7 changes: 3 additions & 4 deletions libs/vision/src/chessboard_stereo_camera_calib.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ bool mrpt::vision::checkerBoardStereoCalibration(
if (!dat.img_original.isExternallyStored())
{
// Checkboad as color image:
dat.img_original.colorImage(dat.img_checkboard);
dat.img_checkboard = dat.img_original.colorImage();
dat.img_checkboard.drawChessboardCorners(
dat.detected_corners, check_size.x, check_size.y);
}
Expand Down Expand Up @@ -199,8 +199,8 @@ bool mrpt::vision::checkerBoardStereoCalibration(
if (has_to_redraw_corners)
{
// Checkboad as color image:
images[i].right.img_original.colorImage(
images[i].right.img_checkboard);
images[i].right.img_checkboard =
images[i].right.img_original.colorImage();
images[i].right.img_checkboard.drawChessboardCorners(
images[i].right.detected_corners, check_size.x,
check_size.y);
Expand Down Expand Up @@ -276,7 +276,6 @@ bool mrpt::vision::checkerBoardStereoCalibration(
// Run stereo calibration in two stages:
// (0) Estimate all parameters except distortion
// (1) Estimate all parameters, using as starting point the guess from
// (0)
// ===============================================================================
size_t nUnknownsCamParams = 0;
size_t iter = 0;
Expand Down
5 changes: 4 additions & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<package format="3">
<name>mrpt2</name>
<!-- Before updating version number, read [MRPT_ROOT]/version_prefix.txt first -->
<version>2.11.8</version>
<version>2.11.9</version>
<description>Mobile Robot Programming Toolkit (MRPT) version 2.x</description>

<author email="joseluisblancoc@gmail.com">Jose-Luis Blanco-Claraco</author>
Expand Down Expand Up @@ -72,6 +72,9 @@
<depend condition="$ROS_VERSION == 1">roscpp</depend>
<depend condition="$ROS_VERSION == 2">rclcpp</depend>

<!-- for rosbag2rawlog (ROS 1 only, ROS 2 version lives in the mrpt_navigation repository) -->
<depend condition="$ROS_VERSION == 1">tf2_geometry_msgs</depend>

<doc_depend>doxygen</doc_depend>

<!-- Minimum entries to release non-catkin pkgs: -->
Expand Down
2 changes: 1 addition & 1 deletion version_prefix.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
2.11.8
2.11.9
# IMPORTANT: This file is parsed by CMake, don't add any comment to
# the first line.
# This file is used in both Windows and Linux scripts to automatically
Expand Down

0 comments on commit 5c35862

Please sign in to comment.