Skip to content

Commit

Permalink
more fixes for bindings
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Apr 27, 2023
1 parent a1b19a9 commit 2ac3893
Show file tree
Hide file tree
Showing 19 changed files with 219 additions and 186 deletions.
16 changes: 8 additions & 8 deletions libs/poses/include/mrpt/poses/CPose3DGridTemplate.h
Original file line number Diff line number Diff line change
Expand Up @@ -285,14 +285,14 @@ class CPose3DGridTemplate
v = val;
}

auto getSizeX() const { return m_sizeX; }
auto getSizeY() const { return m_sizeY; }
auto getSizeZ() const { return m_sizeZ; }
auto getSizeYaw() const { return m_sizeYaw; }
auto getSizePitch() const { return m_sizePitch; }
auto getSizeRoll() const { return m_sizeRoll; }

auto getTotalVoxelCount() const { return m_size_xyzYPR; }
uint32_t getSizeX() const { return m_sizeX; }
uint32_t getSizeY() const { return m_sizeY; }
uint32_t getSizeZ() const { return m_sizeZ; }
uint32_t getSizeYaw() const { return m_sizeYaw; }
uint32_t getSizePitch() const { return m_sizePitch; }
uint32_t getSizeRoll() const { return m_sizeRoll; }

uint32_t getTotalVoxelCount() const { return m_size_xyzYPR; }

const std::vector<T>& getData() const { return m_data; }
std::vector<T>& getData() { return m_data; }
Expand Down
11 changes: 5 additions & 6 deletions libs/slam/include/mrpt/slam/CMetricMapBuilder.h
Original file line number Diff line number Diff line change
Expand Up @@ -113,18 +113,17 @@ class CMetricMapBuilder : public mrpt::system::COutputLogger
struct TOptions
{
TOptions(mrpt::system::VerbosityLevel& verb_level_ref)
: verbosity_level(verb_level_ref),
enableMapUpdating(true),
debugForceInsertion(false),
alwaysInsertByClass()
: verbosity_level(verb_level_ref)
{
}

mrpt::system::VerbosityLevel& verbosity_level;

/** Enable map updating, default is true. */
bool enableMapUpdating;
bool enableMapUpdating = true;

/** Always insert into map. Default is false: detect if necesary. */
bool debugForceInsertion;
bool debugForceInsertion = false;

/** A list of observation classes (derived from mrpt::obs::CObservation)
* which will be always inserted in the map, disregarding the minimum
Expand Down
3 changes: 2 additions & 1 deletion libs/slam/src/slam/CMonteCarloLocalization2D.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,10 @@
#include <mrpt/obs/CSensoryFrame.h>
#include <mrpt/random.h>
#include <mrpt/slam/CMonteCarloLocalization2D.h>
#include <mrpt/slam/PF_aux_structs.h>
#include <mrpt/system/CTicTac.h>

#include "PF_aux_structs.h"

using namespace mrpt;
using namespace mrpt::bayes;
using namespace mrpt::poses;
Expand Down
3 changes: 2 additions & 1 deletion libs/slam/src/slam/CMonteCarloLocalization3D.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,8 @@
#include <mrpt/math/utils.h>
#include <mrpt/obs/CSensoryFrame.h>
#include <mrpt/slam/CMonteCarloLocalization3D.h>
#include <mrpt/slam/PF_aux_structs.h>

#include "PF_aux_structs.h"

using namespace std;
using namespace mrpt;
Expand Down
3 changes: 2 additions & 1 deletion libs/slam/src/slam/CMultiMetricMapPDF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,11 @@
#include <mrpt/poses/CPosePDFGrid.h>
#include <mrpt/random.h>
#include <mrpt/serialization/CArchive.h>
#include <mrpt/slam/PF_aux_structs.h>
#include <mrpt/system/CTicTac.h>
#include <mrpt/system/os.h>

#include "PF_aux_structs.h"

using namespace mrpt;
using namespace mrpt::math;
using namespace mrpt::slam;
Expand Down
3 changes: 2 additions & 1 deletion libs/slam/src/slam/CMultiMetricMapPDF_RBPF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,10 @@
#include <mrpt/poses/CPosePDFGaussian.h>
#include <mrpt/poses/CPosePDFGrid.h>
#include <mrpt/random.h>
#include <mrpt/slam/PF_aux_structs.h>
#include <mrpt/system/CTicTac.h>

#include "PF_aux_structs.h"

using namespace mrpt;
using namespace mrpt::bayes;
using namespace mrpt::math;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
namespace mrpt::slam::detail
{
using namespace mrpt;
using namespace mrpt::math;
using namespace std;

/** Auxiliary structure used in KLD-sampling in particle filters \sa
Expand Down
53 changes: 2 additions & 51 deletions libs/vision/include/mrpt/vision/utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ void openCV_cross_correlation(
* image.
* \param A [IN] The 3x3 intrinsic parameters matrix for the camera.
* \return The mrpt::math::TPoint3D containing the output unitary vector.
* \sa buildIntrinsicParamsMatrix, defaultIntrinsicParamsMatrix, TPixelCoordf
* \sa buildIntrinsicParamsMatrix, TPixelCoordf
*/
mrpt::math::TPoint3D pixelTo3D(
const mrpt::img::TPixelCoordf& xy, const mrpt::math::CMatrixDouble33& A);
Expand All @@ -90,61 +90,12 @@ mrpt::math::TPoint3D pixelTo3D(
</table>
* See also the tutorial discussing the <a
rhref="http://www.mrpt.org/Camera_Parameters">camera model parameters</a>.
* \sa defaultIntrinsicParamsMatrix, pixelTo3D
* \sa pixelTo3D
*/
mrpt::math::CMatrixDouble33 buildIntrinsicParamsMatrix(
const double focalLengthX, const double focalLengthY, const double centerX,
const double centerY);

/** Returns the stored, default intrinsic params matrix for a given camera:
* \param camIndex [IN] Posible values are listed next.
* \param resolutionX [IN] The number of pixel columns
* \param resolutionY [IN] The number of pixel rows
*
* The matrix is generated for the indicated camera resolution configuration.
* The following table summarizes the current supported cameras and the values
as
* ratios of the corresponding horz. or vert. resolution:<br>
<center><table>
<tr>
<td><center><b>camIndex</b></center></td>
<td><center><b>Manufacturer</b></center></td>
<td><center><b>Camera model</b></center></td>
<td><center><b>fx</b></center></td>
<td><center><b>fy</b></center></td>
<td><center><b>cx</b></center></td>
<td><center><b>cy</b></center></td>
</tr>
<tr>
<td><center>0</center></td>
<td><center>Point Grey Research</center></td>
<td><center>Bumblebee</center></td>
<td><center>0.79345</center></td>
<td><center>1.05793</center></td>
<td><center>0.55662</center></td>
<td><center>0.52692</center></td>
</tr>
<tr>
<td><center>1</center></td>
<td><center>Sony</center></td>
<td><center>???</center></td>
<td><center>0.95666094</center></td>
<td><center>1.3983423f</center></td>
<td><center>0.54626328f</center></td>
<td><center>0.4939191f</center></td>
</tr>
</table>
</center>
* \sa buildIntrinsicParamsMatrix, pixelTo3D
*/
mrpt::math::CMatrixDouble33 defaultIntrinsicParamsMatrix(
unsigned int camIndex = 0, unsigned int resolutionX = 320,
unsigned int resolutionY = 240);

/** Computes the mean squared distance between a set of 3D correspondences
* ...
*/
Expand Down
40 changes: 1 addition & 39 deletions libs/vision/src/vision_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -168,43 +168,6 @@ CMatrixDouble33 vision::buildIntrinsicParamsMatrix(
return A;
}

/*-------------------------------------------------------------
defaultIntrinsicParamsMatrix
-------------------------------------------------------------*/
CMatrixDouble33 vision::defaultIntrinsicParamsMatrix(
unsigned int camIndex, unsigned int resX, unsigned int resY)
{
float fx, fy, cx, cy;

switch (camIndex)
{
case 0:
// Bumblebee:
fx = 0.79345f;
fy = 1.05793f;
cx = 0.55662f;
cy = 0.52692f;
break;

case 1:
// Sony:
fx = 0.95666094f;
fy = 1.3983423f;
cx = 0.54626328f;
cy = 0.4939191f;
break;

default:
{
THROW_EXCEPTION_FMT(
"Unknown camera index!! for 'camIndex'=%u", camIndex);
}
}

return buildIntrinsicParamsMatrix(
resX * fx, resY * fy, resX * cx, resY * cy);
}

/*-------------------------------------------------------------
computeMsd
-------------------------------------------------------------*/
Expand Down Expand Up @@ -1893,9 +1856,8 @@ void vision::computeStereoRectificationMaps(
} // end computeStereoRectificationMaps

TStereoSystemParams::TStereoSystemParams()

{
K = defaultIntrinsicParamsMatrix(0, 640, 480);
// K = defaultIntrinsicParamsMatrix(0, 640, 480);
F.setZero();
F(1, 2) = -1;
F(2, 1) = 1;
Expand Down
2 changes: 1 addition & 1 deletion python/.clang-format
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
DisableFormat: true
SortIncludes: Never
SortIncludes: false

3 changes: 3 additions & 0 deletions python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,9 @@ target_link_libraries(pymrpt PUBLIC
mrpt::gui
mrpt::nav
)

target_include_directories(pymrpt PRIVATE ".")

target_compile_definitions(pymrpt PRIVATE
PYBIND11_MAJOR_VERSION=${PYBIND11_MAJOR_VERSION}
PYBIND11_MINOR_VERSION=${PYBIND11_MINOR_VERSION}
Expand Down
1 change: 0 additions & 1 deletion python/all_wrapped_mrpt_headers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -414,7 +414,6 @@
#include <mrpt/slam/CRangeBearingKFSLAM.h>
#include <mrpt/slam/CRangeBearingKFSLAM2D.h>
#include <mrpt/slam/CRejectionSamplingRangeOnlyLocalization.h>
#include <mrpt/slam/PF_aux_structs.h>
#include <mrpt/slam/PF_implementations.h>
#include <mrpt/slam/PF_implementations_data.h>
#include <mrpt/slam/TKLDParams.h>
Expand Down
10 changes: 0 additions & 10 deletions python/patch-001.diff

This file was deleted.

10 changes: 0 additions & 10 deletions python/patch-002.diff

This file was deleted.

11 changes: 0 additions & 11 deletions python/patch-004.diff

This file was deleted.

12 changes: 0 additions & 12 deletions python/patch-005.diff

This file was deleted.

10 changes: 10 additions & 0 deletions python/patch-006.diff
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
--- generated-sources-pybind/mrpt/serialization/CArchive_1.cpp 2023-04-27 23:31:05.248357920 +0200
+++ generated-sources-pybind/mrpt/serialization/CArchive_1.new.cpp 2023-04-27 23:38:49.302474957 +0200
@@ -15,6 +15,7 @@
#include <string>
#include <pybind11/stl.h>

+#include <mrpt/serialization/CMessage.h>

#ifndef BINDER_PYBIND11_TYPE_CASTER
#define BINDER_PYBIND11_TYPE_CASTER
Loading

0 comments on commit 2ac3893

Please sign in to comment.