Skip to content

Commit

Permalink
Update wrapper
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Sep 24, 2024
1 parent c271521 commit 909c946
Show file tree
Hide file tree
Showing 6 changed files with 79 additions and 31 deletions.
4 changes: 2 additions & 2 deletions python/src/mrpt/obs/CObservation2DRangeScan.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@
PYBIND11_MAKE_OPAQUE(std::shared_ptr<void>)
#endif

// mrpt::obs::CObservation2DRangeScan file:mrpt/obs/CObservation2DRangeScan.h line:55
// mrpt::obs::CObservation2DRangeScan file:mrpt/obs/CObservation2DRangeScan.h line:59
struct PyCallBack_mrpt_obs_CObservation2DRangeScan : public mrpt::obs::CObservation2DRangeScan {
using mrpt::obs::CObservation2DRangeScan::CObservation2DRangeScan;

Expand Down Expand Up @@ -242,7 +242,7 @@ struct PyCallBack_mrpt_obs_CObservation2DRangeScan : public mrpt::obs::CObservat

void bind_mrpt_obs_CObservation2DRangeScan(std::function< pybind11::module &(std::string const &namespace_) > &M)
{
{ // mrpt::obs::CObservation2DRangeScan file:mrpt/obs/CObservation2DRangeScan.h line:55
{ // mrpt::obs::CObservation2DRangeScan file:mrpt/obs/CObservation2DRangeScan.h line:59
pybind11::class_<mrpt::obs::CObservation2DRangeScan, std::shared_ptr<mrpt::obs::CObservation2DRangeScan>, PyCallBack_mrpt_obs_CObservation2DRangeScan, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservation2DRangeScan", "A \"CObservation\"-derived class that represents a 2D range scan measurement\n (typically from a laser scanner).\n The data structures are generic enough to hold a wide variety of 2D\n scanners and \"3D\" planar rotating 2D lasers.\n\n These are the most important data fields:\n - Scan ranges: A vector of float values with all the range measurements\n [meters]. Access via `CObservation2DRangeScan::getScanRange()` and\n `CObservation2DRangeScan::setScanRange()`.\n - Range validity: A vector (of identical size to scan), it holds\n `true` for those ranges than are valid (i.e. will be zero for non-reflected\n rays, etc.), `false` for scan rays without a valid lidar return.\n - Reflection intensity: A vector (of identical size to scan) a\n unitless int values representing the relative strength of each return. Higher\n values indicate a more intense return. This is useful for filtering out low\n intensity (noisy) returns or detecting intense landmarks.\n - CObservation2DRangeScan::aperture: The field-of-view of the scanner,\n in radians (typically, M_PI = 180deg).\n - CObservation2DRangeScan::sensorPose: The 6D location of the sensor on\n the robot reference frame (default=at the origin), i.e. wrt `base_link`\n following ROS conventions.\n - CObservation2DRangeScan::rightToLeft: The scanning direction:\n true=counterclockwise (default), false=clockwise.\n\n Note that the *angle of each range* in the vectors above is implicitly\n defined by the index within the vector.\n \n\n CObservation, CPointsMap, T2DScanProperties\n \n\n\n ");
cl.def( pybind11::init( [](){ return new mrpt::obs::CObservation2DRangeScan(); }, [](){ return new PyCallBack_mrpt_obs_CObservation2DRangeScan(); } ) );
cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservation2DRangeScan const &o){ return new PyCallBack_mrpt_obs_CObservation2DRangeScan(o); } ) );
Expand Down
4 changes: 3 additions & 1 deletion python/src/mrpt/opengl/CArrow.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -848,6 +848,8 @@ void bind_mrpt_opengl_CArrow(std::function< pybind11::module &(std::string const
cl.def("clear", (void (mrpt::opengl::CAssimpModel::*)()) &mrpt::opengl::CAssimpModel::clear, "Empty the object \n\nC++: mrpt::opengl::CAssimpModel::clear() --> void");
cl.def("traceRay", (bool (mrpt::opengl::CAssimpModel::*)(const class mrpt::poses::CPose3D &, double &) const) &mrpt::opengl::CAssimpModel::traceRay, "C++: mrpt::opengl::CAssimpModel::traceRay(const class mrpt::poses::CPose3D &, double &) const --> bool", pybind11::arg("o"), pybind11::arg("dist"));
cl.def("internalBoundingBoxLocal", (struct mrpt::math::TBoundingBox_<float> (mrpt::opengl::CAssimpModel::*)() const) &mrpt::opengl::CAssimpModel::internalBoundingBoxLocal, "C++: mrpt::opengl::CAssimpModel::internalBoundingBoxLocal() const --> struct mrpt::math::TBoundingBox_<float>");
cl.def("split_triangles_rendering_bbox", (void (mrpt::opengl::CAssimpModel::*)(const float)) &mrpt::opengl::CAssimpModel::split_triangles_rendering_bbox, "Enable (or disable if set to .0f) a feature in which textured triangles\n are split into different renderizable smaller objects.\n This is required only for semitransparent objects with overlaping regions.\n\nC++: mrpt::opengl::CAssimpModel::split_triangles_rendering_bbox(const float) --> void", pybind11::arg("bbox_size"));
cl.def("split_triangles_rendering_bbox", (float (mrpt::opengl::CAssimpModel::*)() const) &mrpt::opengl::CAssimpModel::split_triangles_rendering_bbox, "C++: mrpt::opengl::CAssimpModel::split_triangles_rendering_bbox() const --> float");
cl.def("assign", (class mrpt::opengl::CAssimpModel & (mrpt::opengl::CAssimpModel::*)(const class mrpt::opengl::CAssimpModel &)) &mrpt::opengl::CAssimpModel::operator=, "C++: mrpt::opengl::CAssimpModel::operator=(const class mrpt::opengl::CAssimpModel &) --> class mrpt::opengl::CAssimpModel &", pybind11::return_value_policy::automatic, pybind11::arg(""));

{ // mrpt::opengl::CAssimpModel::LoadFlags file:mrpt/opengl/CAssimpModel.h line:84
Expand All @@ -866,7 +868,7 @@ void bind_mrpt_opengl_CArrow(std::function< pybind11::module &(std::string const

}

{ // mrpt::opengl::CAssimpModel::TInfoPerTexture file:mrpt/opengl/CAssimpModel.h line:123
{ // mrpt::opengl::CAssimpModel::TInfoPerTexture file:mrpt/opengl/CAssimpModel.h line:133
auto & enclosing_class = cl;
pybind11::class_<mrpt::opengl::CAssimpModel::TInfoPerTexture, std::shared_ptr<mrpt::opengl::CAssimpModel::TInfoPerTexture>> cl(enclosing_class, "TInfoPerTexture", "");
cl.def( pybind11::init( [](){ return new mrpt::opengl::CAssimpModel::TInfoPerTexture(); } ) );
Expand Down
28 changes: 0 additions & 28 deletions python/src/mrpt/slam/CRejectionSamplingRangeOnlyLocalization.cpp
Original file line number Diff line number Diff line change
@@ -1,24 +1,16 @@
#include <chrono>
#include <ios>
#include <iterator>
#include <memory>
#include <mrpt/core/Clock.h>
#include <mrpt/maps/CLandmarksMap.h>
#include <mrpt/maps/CMetricMap.h>
#include <mrpt/maps/CSimpleMap.h>
#include <mrpt/maps/CSimplePointsMap.h>
#include <mrpt/maps/TMetricMapInitializer.h>
#include <mrpt/maps/metric_map_types.h>
#include <mrpt/math/CMatrixDynamic.h>
#include <mrpt/math/CMatrixFixed.h>
#include <mrpt/math/CQuaternion.h>
#include <mrpt/math/CVectorDynamic.h>
#include <mrpt/math/TBoundingBox.h>
#include <mrpt/math/TPoint2D.h>
#include <mrpt/math/TPoint3D.h>
#include <mrpt/math/TPose2D.h>
#include <mrpt/math/TPose3D.h>
#include <mrpt/math/TPose3DQuat.h>
#include <mrpt/math/math_frwds.h>
#include <mrpt/math/matrix_size_t.h>
#include <mrpt/obs/CObservation.h>
Expand All @@ -27,7 +19,6 @@
#include <mrpt/obs/CObservationBearingRange.h>
#include <mrpt/obs/CObservationImage.h>
#include <mrpt/obs/CObservationStereoImages.h>
#include <mrpt/obs/CSensoryFrame.h>
#include <mrpt/opengl/CSetOfObjects.h>
#include <mrpt/poses/CPoint2D.h>
#include <mrpt/poses/CPoint3D.h>
Expand All @@ -37,15 +28,12 @@
#include <mrpt/poses/CPoseOrPoint.h>
#include <mrpt/rtti/CObject.h>
#include <mrpt/slam/CRejectionSamplingRangeOnlyLocalization.h>
#include <mrpt/slam/observations_overlap.h>
#include <mrpt/tfest/TMatchingPair.h>
#include <mrpt/typemeta/static_string.h>
#include <mrpt/vision/CFeatureExtraction.h>
#include <optional>
#include <ostream>
#include <ratio>
#include <sstream> // __str__
#include <streambuf>
#include <string>
#include <vector>

Expand Down Expand Up @@ -106,20 +94,4 @@ void bind_mrpt_slam_CRejectionSamplingRangeOnlyLocalization(std::function< pybin
cl.def("setParams", (bool (mrpt::slam::CRejectionSamplingRangeOnlyLocalization::*)(const class mrpt::maps::CLandmarksMap &, const class mrpt::obs::CObservationBeaconRanges &, float, const class mrpt::poses::CPose2D &, float, bool)) &mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams, "The parameters used in the generation of random samples:\n \n\n The map containing the N beacons (indexed by their\n \"beacon ID\"s). Only the mean 3D position of the beacons is used, the\n covariance is ignored.\n \n\n An observation with, at least ONE range measurement.\n \n\n The standard deviation of the \"range measurement\n noise\".\n \n\n The height of the robot on the floor (default=0). Note\n that the beacon sensor on the robot may be at a different height,\n according to data within the observation object.\n \n\n Whether to make a simple check for potential\n good angles from the beacons to generate samples (disable to speed-up the\n preparation vs. making slower the drawn).\n This method fills out the member \"m_dataPerBeacon\".\n \n\n true if at least ONE beacon has been successfully loaded, false\n otherwise. In this case do not call \"rejectionSampling\" or an exception\n will be launch, since there is no information to generate samples.\n\nC++: mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(const class mrpt::maps::CLandmarksMap &, const class mrpt::obs::CObservationBeaconRanges &, float, const class mrpt::poses::CPose2D &, float, bool) --> bool", pybind11::arg("beaconsMap"), pybind11::arg("observation"), pybind11::arg("sigmaRanges"), pybind11::arg("oldPose"), pybind11::arg("robot_z"), pybind11::arg("autoCheckAngleRanges"));
cl.def("assign", (class mrpt::slam::CRejectionSamplingRangeOnlyLocalization & (mrpt::slam::CRejectionSamplingRangeOnlyLocalization::*)(const class mrpt::slam::CRejectionSamplingRangeOnlyLocalization &)) &mrpt::slam::CRejectionSamplingRangeOnlyLocalization::operator=, "C++: mrpt::slam::CRejectionSamplingRangeOnlyLocalization::operator=(const class mrpt::slam::CRejectionSamplingRangeOnlyLocalization &) --> class mrpt::slam::CRejectionSamplingRangeOnlyLocalization &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
// mrpt::slam::observationsOverlap(const class mrpt::obs::CObservation *, const class mrpt::obs::CObservation *, const class mrpt::poses::CPose3D *) file:mrpt/slam/observations_overlap.h line:26
M("mrpt::slam").def("observationsOverlap", [](const class mrpt::obs::CObservation * a0, const class mrpt::obs::CObservation * a1) -> double { return mrpt::slam::observationsOverlap(a0, a1); }, "", pybind11::arg("o1"), pybind11::arg("o2"));
M("mrpt::slam").def("observationsOverlap", (double (*)(const class mrpt::obs::CObservation *, const class mrpt::obs::CObservation *, const class mrpt::poses::CPose3D *)) &mrpt::slam::observationsOverlap, "Estimates the \"overlap\" or \"matching ratio\" of two observations (range\n [0,1]), possibly taking into account their relative positions.\n \n\n This is used in mrpt::slam::CIncrementalMapPartitioner\n\nC++: mrpt::slam::observationsOverlap(const class mrpt::obs::CObservation *, const class mrpt::obs::CObservation *, const class mrpt::poses::CPose3D *) --> double", pybind11::arg("o1"), pybind11::arg("o2"), pybind11::arg("pose_o2_wrt_o1"));

// mrpt::slam::observationsOverlap(const class std::shared_ptr<class mrpt::obs::CObservation> &, const class std::shared_ptr<class mrpt::obs::CObservation> &, const class mrpt::poses::CPose3D *) file:mrpt/slam/observations_overlap.h line:35
M("mrpt::slam").def("observationsOverlap", [](const class std::shared_ptr<class mrpt::obs::CObservation> & a0, const class std::shared_ptr<class mrpt::obs::CObservation> & a1) -> double { return mrpt::slam::observationsOverlap(a0, a1); }, "", pybind11::arg("o1"), pybind11::arg("o2"));
M("mrpt::slam").def("observationsOverlap", (double (*)(const class std::shared_ptr<class mrpt::obs::CObservation> &, const class std::shared_ptr<class mrpt::obs::CObservation> &, const class mrpt::poses::CPose3D *)) &mrpt::slam::observationsOverlap, "Estimates the \"overlap\" or \"matching ratio\" of two observations (range\n [0,1]), possibly taking into account their relative positions.\n \n\n This is used in mrpt::slam::CIncrementalMapPartitioner\n\nC++: mrpt::slam::observationsOverlap(const class std::shared_ptr<class mrpt::obs::CObservation> &, const class std::shared_ptr<class mrpt::obs::CObservation> &, const class mrpt::poses::CPose3D *) --> double", pybind11::arg("o1"), pybind11::arg("o2"), pybind11::arg("pose_o2_wrt_o1"));

// mrpt::slam::observationsOverlap(const class mrpt::obs::CSensoryFrame &, const class mrpt::obs::CSensoryFrame &, const class mrpt::poses::CPose3D *) file:mrpt/slam/observations_overlap.h line:49
M("mrpt::slam").def("observationsOverlap", [](const class mrpt::obs::CSensoryFrame & a0, const class mrpt::obs::CSensoryFrame & a1) -> double { return mrpt::slam::observationsOverlap(a0, a1); }, "", pybind11::arg("sf1"), pybind11::arg("sf2"));
M("mrpt::slam").def("observationsOverlap", (double (*)(const class mrpt::obs::CSensoryFrame &, const class mrpt::obs::CSensoryFrame &, const class mrpt::poses::CPose3D *)) &mrpt::slam::observationsOverlap, "Estimates the \"overlap\" or \"matching ratio\" of two set of observations\n (range [0,1]), possibly taking into account their relative positions.\n This method computes the average between each of the observations in each\n SF.\n \n\n This is used in mrpt::slam::CIncrementalMapPartitioner\n\nC++: mrpt::slam::observationsOverlap(const class mrpt::obs::CSensoryFrame &, const class mrpt::obs::CSensoryFrame &, const class mrpt::poses::CPose3D *) --> double", pybind11::arg("sf1"), pybind11::arg("sf2"), pybind11::arg("pose_sf2_wrt_sf1"));

// mrpt::slam::observationsOverlap(const class std::shared_ptr<class mrpt::obs::CSensoryFrame> &, const class std::shared_ptr<class mrpt::obs::CSensoryFrame> &, const class mrpt::poses::CPose3D *) file:mrpt/slam/observations_overlap.h line:60
M("mrpt::slam").def("observationsOverlap", [](const class std::shared_ptr<class mrpt::obs::CSensoryFrame> & a0, const class std::shared_ptr<class mrpt::obs::CSensoryFrame> & a1) -> double { return mrpt::slam::observationsOverlap(a0, a1); }, "", pybind11::arg("sf1"), pybind11::arg("sf2"));
M("mrpt::slam").def("observationsOverlap", (double (*)(const class std::shared_ptr<class mrpt::obs::CSensoryFrame> &, const class std::shared_ptr<class mrpt::obs::CSensoryFrame> &, const class mrpt::poses::CPose3D *)) &mrpt::slam::observationsOverlap, "Estimates the \"overlap\" or \"matching ratio\" of two set of observations\n (range [0,1]), possibly taking into account their relative positions.\n This method computes the average between each of the observations in each\n SF.\n \n\n This is used in mrpt::slam::CIncrementalMapPartitioner\n\nC++: mrpt::slam::observationsOverlap(const class std::shared_ptr<class mrpt::obs::CSensoryFrame> &, const class std::shared_ptr<class mrpt::obs::CSensoryFrame> &, const class mrpt::poses::CPose3D *) --> double", pybind11::arg("sf1"), pybind11::arg("sf2"), pybind11::arg("pose_sf2_wrt_sf1"));

}
Loading

0 comments on commit 909c946

Please sign in to comment.