Skip to content

Commit

Permalink
Merge branch 'develop'
Browse files Browse the repository at this point in the history
jlblancoc committed Mar 10, 2024
2 parents 047df86 + a5992be commit 6763374
Showing 55 changed files with 2,507 additions and 2,544 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -78,7 +78,7 @@ sudo apt install ros-$ROS_DISTRO-mrpt2
| ROS1 Noetic @ u20.04 | [![Build Status](https://build.ros.org/job/Ndev__mrpt2__ubuntu_focal_amd64/badge/icon)](https://build.ros.org/job/Ndev__mrpt2__ubuntu_focal_amd64/) | [![Version](https://img.shields.io/ros/v/noetic/mrpt2)](https://index.ros.org/search/?term=mrpt2) | [![Build Status](https://build.ros.org/job/Nbin_uF64__mrpt2__ubuntu_focal_amd64__binary/badge/icon)](https://build.ros.org/job/Nbin_uF64__mrpt2__ubuntu_focal_amd64__binary/) |
| ROS2 Humble @ u22.04 | [![Build Status](https://build.ros2.org/job/Hdev__mrpt2__ubuntu_jammy_amd64/badge/icon)](https://build.ros2.org/job/Hdev__mrpt2__ubuntu_jammy_amd64/) | [![Version](https://img.shields.io/ros/v/humble/mrpt2)](https://index.ros.org/search/?term=mrpt2) | [![Build Status](https://build.ros2.org/job/Hbin_uJ64__mrpt2__ubuntu_jammy_amd64__binary/badge/icon)](https://build.ros2.org/job/Hbin_uJ64__mrpt2__ubuntu_jammy_amd64__binary/) |
| ROS2 Iron @ u22.04 | [![Build Status](https://build.ros2.org/job/Idev__mrpt2__ubuntu_jammy_amd64/badge/icon)](https://build.ros2.org/job/Idev__mrpt2__ubuntu_jammy_amd64/) | [![Version](https://img.shields.io/ros/v/iron/mrpt2)](https://index.ros.org/search/?term=mrpt2) | [![Build Status](https://build.ros2.org/job/Ibin_uJ64__mrpt2__ubuntu_jammy_amd64__binary/badge/icon)](https://build.ros2.org/job/Ibin_uJ64__mrpt2__ubuntu_jammy_amd64__binary/) |
| ROS2 Rolling @ u22.04 | [![Build Status](https://build.ros2.org/job/Rdev__mrpt2__ubuntu_jammy_amd64/badge/icon)](https://build.ros2.org/job/Rdev__mrpt2__ubuntu_jammy_amd64/) | [![Version](https://img.shields.io/ros/v/rolling/mrpt2)](https://index.ros.org/search/?term=mrpt2) | [![Build Status](https://build.ros2.org/job/Rbin_uJ64__mrpt2__ubuntu_jammy_amd64__binary/badge/icon)](https://build.ros2.org/job/Rbin_uJ64__mrpt2__ubuntu_jammy_amd64__binary/) |
| ROS2 Rolling @ u24.04 | [![Build Status](https://build.ros2.org/job/Rdev__mrpt2__ubuntu_noble_amd64/badge/icon)](https://build.ros2.org/job/Rdev__mrpt2__ubuntu_noble_amd64/) | [![Version](https://img.shields.io/ros/v/rolling/mrpt2)](https://index.ros.org/search/?term=mrpt2) | [![Build Status](https://build.ros2.org/job/Rbin_uN64__mrpt2__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Rbin_uN64__mrpt2__ubuntu_noble_amd64__binary/) |

| EOL Distro | Last release |
|---|---|
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.11-{branch}-build{build}
version: 2.11.12-{branch}-build{build}

os: Visual Studio 2019

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.12: Released March 10th, 2024
- Changes in libraries:
- \ref mrpt_obs_grp:
- Fix compiler error on invocation of template mrpt::obs::CObservationGPS::getMsgByClassPtr()
- Add field mrpt::obs::CObservationGPS::covariance_enu for easier interoperability with ROS.
- API simplified: replace custom `mrpt::obs::gnss::gnss_message_ptr` with a `std::shared_ptr<>`.
- mrpt::obs::CObservationRobotPose::getDescriptionAsText(): add human-readable pose uncertainties.
- BUG FIXES:
- Fix wrong encoding of grayscale images in mrpt::ros1bridge::toROS() and mrpt::ros2bridge::toROS().
- Correctly return true/false in conversion of GPS observation in mrpt::ros1bridge::toROS() and mrpt::ros2bridge::toROS() depending on whether there is a valid GGA message.
- mrpt::obs::CObservationComment: Missing serialization of sensorLabel.

# Version 2.11.11: Released March 5th, 2024
- Changes in libraries:
- \ref mrpt_ros1bridge_grp:
5 changes: 4 additions & 1 deletion libs/hwdrivers/include/mrpt/hwdrivers/CGPSInterface.h
Original file line number Diff line number Diff line change
@@ -355,8 +355,11 @@ class CGPSInterface : public mrpt::system::COutputLogger, public CGenericSensor
/** Queue out now the messages in \a m_just_parsed_messages, leaving it
* empty */
void flushParsedMessagesNow();

/** A private copy of the last received gps datum */
mrpt::obs::CObservationGPS m_just_parsed_messages;
mrpt::obs::CObservationGPS::Ptr m_parsed_messages =
mrpt::obs::CObservationGPS::Create();

/** Used in getLastGGA() */
std::string m_last_GGA;
}; // end class
39 changes: 20 additions & 19 deletions libs/hwdrivers/src/CGPSInterface.cpp
Original file line number Diff line number Diff line change
@@ -375,15 +375,14 @@ void CGPSInterface::doProcess()
{
if (m_verbose)
cout << "[CGPSInterface] Initial timestamp: "
<< mrpt::system::timeToString(
m_just_parsed_messages.timestamp)
<< mrpt::system::timeToString(m_parsed_messages->timestamp)
<< endl;
// Check if the initial timestamp seems to be OK (not a spurio one)
TTimeStamp tmNow = mrpt::system::now();
const double tdif = mrpt::system::timeDifference(
m_just_parsed_messages.timestamp, tmNow);
m_parsed_messages->timestamp, tmNow);
if (tdif >= 0 && tdif < 7500 /*Up to two hours*/)
m_last_timestamp = m_just_parsed_messages.timestamp;
m_last_timestamp = m_parsed_messages->timestamp;
else
{
if (m_verbose)
@@ -395,7 +394,7 @@ void CGPSInterface::doProcess()
else
{
const double time_diff = mrpt::system::timeDifference(
m_last_timestamp, m_just_parsed_messages.timestamp);
m_last_timestamp, m_parsed_messages->timestamp);
if (time_diff < 0 || time_diff > 300) // Assert that the current
// timestamp is after the
// previous one and not more
@@ -418,8 +417,8 @@ void CGPSInterface::doProcess()
// a. These GPS data have both synched RMC and GGA data
// don't append observation until we have both data
do_append_obs =
(m_just_parsed_messages.has_GGA_datum() &&
m_just_parsed_messages.has_RMC_datum());
(m_parsed_messages->has_GGA_datum() &&
m_parsed_messages->has_RMC_datum());
} // end-else

if (do_append_obs) flushParsedMessagesNow();
@@ -431,18 +430,19 @@ void CGPSInterface::doProcess()
void CGPSInterface::flushParsedMessagesNow()
{
// Generic observation data:
m_just_parsed_messages.sensorPose = m_sensorPose;
m_parsed_messages->sensorPose = m_sensorPose;
if (m_sensorLabelAppendMsgType)
m_just_parsed_messages.sensorLabel =
m_sensorLabel + string("_") + m_just_parsed_messages.sensorLabel;
m_parsed_messages->sensorLabel =
m_sensorLabel + string("_") + m_parsed_messages->sensorLabel;
else
m_just_parsed_messages.sensorLabel = m_sensorLabel;
m_parsed_messages->sensorLabel = m_sensorLabel;

m_last_timestamp = m_parsed_messages->timestamp;

// Add observation to the output queue:
CObservationGPS::Ptr newObs = std::make_shared<CObservationGPS>();
m_just_parsed_messages.swap(*newObs);
CGenericSensor::appendObservation(newObs);
m_just_parsed_messages.clear();
m_last_timestamp = m_just_parsed_messages.timestamp;
CGenericSensor::appendObservation(m_parsed_messages);

m_parsed_messages = mrpt::obs::CObservationGPS::Create();

// And this means the comms works:
m_GPS_comsWork = true;
@@ -481,7 +481,7 @@ void CGPSInterface::parseBuffer()
m_rx_buffer.pop(); // Not the start of a frame, skip 1 byte
}
if (m_customInit.empty() /* If we are not in old legacy mode */ &&
!m_just_parsed_messages.messages.empty())
!m_parsed_messages->messages.empty())
flushParsedMessagesNow();
} while (m_rx_buffer.size() >= min_bytes);
} // end one parser mode ----------
@@ -508,8 +508,9 @@ void CGPSInterface::parseBuffer()
m_rx_buffer.pop(); // Not the start of a frame, skip 1 byte

if (m_customInit.empty() /* If we are not in old legacy mode */ &&
!m_just_parsed_messages.messages.empty())
!m_parsed_messages->messages.empty())
flushParsedMessagesNow();

} while (m_rx_buffer.size() >= global_min_bytes_max);
} // end AUTO mode ----
}
@@ -605,7 +606,7 @@ bool CGPSInterface::OnConnectionShutdown()
bool CGPSInterface::OnConnectionEstablished()
{
m_last_GGA.clear(); // On comms reset, empty this cache
m_just_parsed_messages.clear();
m_parsed_messages->clear();

// Legacy behavior:
if (!os::_strcmpi(m_customInit.c_str(), "JAVAD") ||
8 changes: 4 additions & 4 deletions libs/hwdrivers/src/CGPSInterface_parser_NMEA.cpp
Original file line number Diff line number Diff line change
@@ -74,15 +74,15 @@ bool CGPSInterface::implement_parser_NMEA(size_t& out_minimum_rx_buf_to_decide)
m_rx_buffer.pop();

// Parse:
const bool did_have_gga = m_just_parsed_messages.has_GGA_datum();
const bool did_have_gga = m_parsed_messages->has_GGA_datum();
if (CGPSInterface::parse_NMEA(
line, m_just_parsed_messages, false /*verbose*/))
line, *m_parsed_messages, false /*verbose*/))
{
// Parsers must set only the part of the msg type:
m_just_parsed_messages.sensorLabel = "NMEA";
m_parsed_messages->sensorLabel = "NMEA";

// Save GGA cache (useful for NTRIP,...)
const bool now_has_gga = m_just_parsed_messages.has_GGA_datum();
const bool now_has_gga = m_parsed_messages->has_GGA_datum();
if (now_has_gga && !did_have_gga) { m_last_GGA = line; }
}
else
24 changes: 12 additions & 12 deletions libs/hwdrivers/src/CGPSInterface_parser_NOVATEL_OEM6.cpp
Original file line number Diff line number Diff line change
@@ -119,16 +119,16 @@ bool CGPSInterface::implement_parser_NOVATEL_OEM6(
<< hdr.msg_id << "\n";
return true;
}
m_just_parsed_messages.messages[msg->message_type] = msg;
m_just_parsed_messages.originalReceivedTimestamp = mrpt::system::now();
m_parsed_messages->messages[msg->message_type] = msg;
m_parsed_messages->originalReceivedTimestamp = mrpt::system::now();
if (!CObservationGPS::GPS_time_to_UTC(
hdr.week, hdr.ms_in_week * 1e-3, num_leap_seconds,
m_just_parsed_messages.timestamp))
m_just_parsed_messages.timestamp = mrpt::system::now();
m_parsed_messages->timestamp))
m_parsed_messages->timestamp = mrpt::system::now();
else
m_just_parsed_messages.has_satellite_timestamp = true;
m_parsed_messages->has_satellite_timestamp = true;

m_just_parsed_messages.sensorLabel = msg->getMessageTypeAsString();
m_parsed_messages->sensorLabel = msg->getMessageTypeAsString();

flushParsedMessagesNow();
return true;
@@ -197,8 +197,8 @@ bool CGPSInterface::implement_parser_NOVATEL_OEM6(
<< hdr.msg_id << "\n";
return true;
}
m_just_parsed_messages.messages[msg->message_type] = msg;
m_just_parsed_messages.originalReceivedTimestamp = mrpt::system::now();
m_parsed_messages->messages[msg->message_type] = msg;
m_parsed_messages->originalReceivedTimestamp = mrpt::system::now();
{
// Detect NV_OEM6_IONUTC msgs to learn about the current leap
// seconds:
@@ -208,12 +208,12 @@ bool CGPSInterface::implement_parser_NOVATEL_OEM6(
}
if (!CObservationGPS::GPS_time_to_UTC(
hdr.week, hdr.ms_in_week * 1e-3, num_leap_seconds,
m_just_parsed_messages.timestamp))
m_just_parsed_messages.timestamp = mrpt::system::now();
m_parsed_messages->timestamp))
m_parsed_messages->timestamp = mrpt::system::now();
else
m_just_parsed_messages.has_satellite_timestamp = true;
m_parsed_messages->has_satellite_timestamp = true;

m_just_parsed_messages.sensorLabel = msg->getMessageTypeAsString();
m_parsed_messages->sensorLabel = msg->getMessageTypeAsString();
flushParsedMessagesNow();
return true;
} // end regular hdr
30 changes: 15 additions & 15 deletions libs/hwdrivers/src/CGPSInterface_unittest.cpp
Original file line number Diff line number Diff line change
@@ -370,19 +370,19 @@ TEST(CGPSInterface, parse_NMEA_stream)
EXPECT_TRUE(obsGPS2);
EXPECT_TRUE(obsGPS3);

const auto* msg1 = obsGPS1->getMsgByClassPtr<gnss::Message_NMEA_GSA>();
EXPECT_TRUE(msg1 != nullptr);
if (!msg1) return;
EXPECT_EQ(msg1->fields.PRNs[0][0], '1');
EXPECT_EQ(msg1->fields.PRNs[0][1], '5');
EXPECT_NEAR(msg1->fields.HDOP, 2.31, 0.1);

const auto* msg2 = obsGPS2->getMsgByClassPtr<gnss::Message_NMEA_GSA>();
EXPECT_TRUE(msg2 != nullptr);

const auto* msg3 = obsGPS3->getMsgByClassPtr<gnss::Message_NMEA_RMC>();
EXPECT_TRUE(msg3 != nullptr);
if (!msg3) return;
EXPECT_NEAR(msg3->fields.longitude_degrees, -2.407810500, 0.0001);
EXPECT_NEAR(msg3->fields.latitude_degrees, 36.829821500, 0.0001);
const auto* msgRMC = obsGPS1->getMsgByClassPtr<gnss::Message_NMEA_RMC>();
EXPECT_TRUE(msgRMC != nullptr);
if (!msgRMC) return;
EXPECT_NEAR(msgRMC->fields.longitude_degrees, -2.407810500, 0.0001);
EXPECT_NEAR(msgRMC->fields.latitude_degrees, 36.829821500, 0.0001);

const auto* msgGSA1 = obsGPS2->getMsgByClassPtr<gnss::Message_NMEA_GSA>();
EXPECT_TRUE(msgGSA1 != nullptr);
if (!msgGSA1) return;
EXPECT_EQ(msgGSA1->fields.PRNs[0][0], '1');
EXPECT_EQ(msgGSA1->fields.PRNs[0][1], '5');
EXPECT_NEAR(msgGSA1->fields.HDOP, 2.31, 0.1);

const auto* msgGSA2 = obsGPS3->getMsgByClassPtr<gnss::Message_NMEA_GSA>();
EXPECT_TRUE(msgGSA2 != nullptr);
}
26 changes: 16 additions & 10 deletions libs/obs/include/mrpt/obs/CObservationGPS.h
Original file line number Diff line number Diff line change
@@ -8,13 +8,15 @@
+------------------------------------------------------------------------+ */
#pragma once

#include <mrpt/math/CMatrixFixed.h>
#include <mrpt/obs/CObservation.h>
#include <mrpt/obs/gnss_messages.h>
#include <mrpt/poses/CPose2D.h>
#include <mrpt/poses/CPose3D.h>
#include <mrpt/serialization/CSerializable.h>

#include <map>
#include <optional>
#include <typeinfo>

namespace mrpt::obs
@@ -28,7 +30,7 @@ namespace mrpt::obs
* indivual messages \b stored in mrpt::obs::CObservationGPS objects.
*
* Supported message types are:
* - NMEA 0183 (ASCII): GGA, RMC
* - NMEA 0183 (ASCII): GGA, RMC, etc.
* - Topcon GRIL (Binary): PZS, SATS
* - Novatel GNSS/SPAN OEM6 (Binary): See list of log packets under namespace
* mrpt::obs::gnss and in enum type mrpt::obs::gnss::gnss_message_type_t
@@ -57,11 +59,9 @@ namespace mrpt::obs
* }
* \endcode
*
* \note <b>[API changed in MRPT 1.4.0]</b> mrpt::obs::CObservationGPS now
* stores message objects in a more flexible way. API clean-up and extended so
* the number of GNSS message types is larger and more scalable.
* \note Porting old code: For example, replace `observation.GGA_datum.XXX` with
* `observation.getMsgByClass<gnss::Message_NMEA_GGA>().fields.XXX`, etc.
* \note Since MRPT 2.11.12 there is an optional field for ENU covariance for
* easier compatibility with ROS messages.
*
* \sa CObservation
* \ingroup mrpt_obs_grp
*/
@@ -77,20 +77,27 @@ class CObservationGPS : public CObservation
* @{ */
/** The sensor pose on the robot/vehicle */
mrpt::poses::CPose3D sensorPose{};

/** The local computer-based timestamp based on the reception of the message
* in the computer. \sa CObservation::timestamp in the base class, which
* should contain the accurate satellite-based UTC timestamp. */
mrpt::system::TTimeStamp originalReceivedTimestamp{INVALID_TIMESTAMP};

/** If true, CObservation::timestamp has been generated from accurate
* satellite clock. Otherwise, no GPS data is available and timestamps are
* based on the local computer clock. */
bool has_satellite_timestamp{false};

/** The main piece of data in this class: a list of GNNS messages.
* Normally users might prefer to access the list via the methods
* CObservationGPS::getMsgByClass() and CObservationGPS::setMsg()
* Typically only one message, may be multiple if all have the same
* timestamp. */
message_list_t messages;

/** If present, it defines the ENU position uncertainty.
*/
std::optional<mrpt::math::CMatrixDouble33> covariance_enu;
/** @} */

/** @name Main API to access to the data fields
@@ -104,7 +111,7 @@ class CObservationGPS : public CObservation
void setMsg(const MSG_CLASS& msg)
{
messages[static_cast<gnss::gnss_message_type_t>(MSG_CLASS::msg_type)]
.set(new MSG_CLASS(msg));
.reset(new MSG_CLASS(msg));
}
/** Returns true if the list \a CObservationGPS::messages contains one of
* the requested type. \sa mrpt::obs::gnss::gnss_message_type_t,
@@ -189,8 +196,8 @@ class CObservationGPS : public CObservation
auto it = messages.find(
static_cast<gnss::gnss_message_type_t>(MSG_CLASS::msg_type));
return it == messages.end()
? dynamic_cast<MSG_CLASS*>(nullptr)
: dynamic_cast<MSG_CLASS*>(it->second.get());
? static_cast<const MSG_CLASS*>(nullptr)
: dynamic_cast<const MSG_CLASS*>(it->second.get());
}

/** Dumps the contents of the observation in a human-readable form to a
@@ -201,7 +208,6 @@ class CObservationGPS : public CObservation
void dumpToConsole(std::ostream& o) const;
/** Empties this observation, clearing the container \a messages */
void clear();
void swap(CObservationGPS& o);

void getSensorPose(mrpt::poses::CPose3D& out_sensorPose) const override
{
37 changes: 1 addition & 36 deletions libs/obs/include/mrpt/obs/gnss_messages_common.h
Original file line number Diff line number Diff line change
@@ -97,42 +97,7 @@ struct gnss_message

/** A smart pointer to a GNSS message. \sa gnss_message,
* mrpt::obs::CObservationGPS */
struct gnss_message_ptr
{
protected:
gnss_message* ptr{nullptr};

public:
/** Ctor (default: nullptr pointer) */
gnss_message_ptr();
/** Makes a copy of the pointee */
gnss_message_ptr(const gnss_message_ptr& o);
/** Assigns a pointer. Memory now belongs to this class. */
explicit gnss_message_ptr(const gnss_message* p);
gnss_message_ptr& operator=(
const gnss_message_ptr& o); // Makes a copy of the pointee
/** Dtor: it frees the pointee memory */
virtual ~gnss_message_ptr();
bool operator==(const gnss_message* o) const { return o == ptr; }
bool operator==(const gnss_message_ptr& o) const { return o.ptr == ptr; }
bool operator!=(const gnss_message* o) const { return o != ptr; }
bool operator!=(const gnss_message_ptr& o) const { return o.ptr != ptr; }
gnss_message*& get() { return ptr; }
const gnss_message* get() const { return ptr; }
gnss_message*& operator->()
{
ASSERT_(ptr);
return ptr;
}
const gnss_message* operator->() const
{
ASSERT_(ptr);
return ptr;
}
/** Replaces the pointee with a new pointer. Its memory now belongs to this
* object, do not free manually. */
void set(gnss_message* p);
};
using gnss_message_ptr = std::shared_ptr<gnss_message>;

#define GNSS_MESSAGE_BINARY_BLOCK(DATA_PTR, DATA_LEN) \
protected: \
9 changes: 7 additions & 2 deletions libs/obs/src/CObservationComment.cpp
Original file line number Diff line number Diff line change
@@ -20,18 +20,23 @@ using namespace mrpt::poses;
// This must be added to any CSerializable class implementation file.
IMPLEMENTS_SERIALIZABLE(CObservationComment, CObservation, mrpt::obs)

uint8_t CObservationComment::serializeGetVersion() const { return 0; }
uint8_t CObservationComment::serializeGetVersion() const { return 1; }
void CObservationComment::serializeTo(mrpt::serialization::CArchive& out) const
{
out << text << timestamp;
out << sensorLabel; // v1
}

void CObservationComment::serializeFrom(
mrpt::serialization::CArchive& in, uint8_t version)
{
switch (version)
{
case 0: in >> text >> timestamp; break;
case 0:
case 1:
in >> text >> timestamp;
if (version >= 1) in >> sensorLabel;
break;
default: MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version);
};
}
43 changes: 25 additions & 18 deletions libs/obs/src/CObservationGPS.cpp
Original file line number Diff line number Diff line change
@@ -12,6 +12,7 @@
#include <mrpt/math/matrix_serialization.h> // for << of matrices
#include <mrpt/obs/CObservationGPS.h>
#include <mrpt/serialization/CArchive.h>
#include <mrpt/serialization/optional_serialization.h>

#include <iomanip>

@@ -23,21 +24,12 @@ using namespace mrpt::math;
// This must be added to any CSerializable class implementation file.
IMPLEMENTS_SERIALIZABLE(CObservationGPS, CObservation, mrpt::obs)

void CObservationGPS::swap(CObservationGPS& o)
{
std::swap(timestamp, o.timestamp);
std::swap(originalReceivedTimestamp, o.originalReceivedTimestamp);
std::swap(has_satellite_timestamp, o.has_satellite_timestamp);
std::swap(sensorLabel, o.sensorLabel);
std::swap(sensorPose, o.sensorPose);
messages.swap(o.messages);
}

uint8_t CObservationGPS::serializeGetVersion() const { return 11; }
uint8_t CObservationGPS::serializeGetVersion() const { return 12; }
void CObservationGPS::serializeTo(mrpt::serialization::CArchive& out) const
{
out << timestamp << originalReceivedTimestamp << sensorLabel << sensorPose;
out << has_satellite_timestamp; // v11
out << covariance_enu; // v12

const uint32_t nMsgs = messages.size();
out << nMsgs;
@@ -54,6 +46,7 @@ void CObservationGPS::serializeFrom(
{
case 10:
case 11:
case 12:
{
in >> timestamp >> originalReceivedTimestamp >> sensorLabel >>
sensorPose;
@@ -62,6 +55,8 @@ void CObservationGPS::serializeFrom(
has_satellite_timestamp =
(this->timestamp != this->originalReceivedTimestamp);

if (version >= 12) in >> covariance_enu;

uint32_t nMsgs;
in >> nMsgs;
for (unsigned i = 0; i < nMsgs; i++)
@@ -248,11 +243,27 @@ void CObservationGPS::serializeFrom(

void CObservationGPS::dumpToStream(std::ostream& out) const
{
if (covariance_enu)
{
out << "ENU covariance:\n" << *covariance_enu << "\n";
// clang-format off
out << "ENU sigmas:\n"
"std_x=" << std::sqrt((*covariance_enu)(0,0)) << "\n"
"std_y=" << std::sqrt((*covariance_enu)(1,1)) << "\n"
"std_z=" << std::sqrt((*covariance_enu)(2,2)) << "\n";
// clang-format on
}
else
{
out << "ENU covariance: (none)\n";
}

out << "\n------------- [CObservationGPS] Dump of " << messages.size()
<< " messages --------------------\n";
for (const auto& m : messages)
m.second->dumpToStream(out);
out << "-------------- [CObservationGPS] End of dump -----------------\n\n";
out << "-------------- [CObservationGPS] End of message dump "
"-----------------\n\n";
}

void CObservationGPS::dumpToConsole(std::ostream& o) const
@@ -265,12 +276,8 @@ mrpt::system::TTimeStamp CObservationGPS::getOriginalReceivedTimeStamp() const
return originalReceivedTimestamp;
}

void CObservationGPS::clear()
{
messages.clear();
timestamp = INVALID_TIMESTAMP;
originalReceivedTimestamp = INVALID_TIMESTAMP;
}
void CObservationGPS::clear() { *this = CObservationGPS(); }

void CObservationGPS::getDescriptionAsText(std::ostream& o) const
{
using namespace mrpt::system; // for the TTimeStamp << operator
18 changes: 15 additions & 3 deletions libs/obs/src/CObservationRobotPose.cpp
Original file line number Diff line number Diff line change
@@ -57,11 +57,23 @@ void CObservationRobotPose::setSensorPose(const CPose3D& newSensorPose)

void CObservationRobotPose::getDescriptionAsText(std::ostream& o) const
{
using namespace std;
CObservation::getDescriptionAsText(o);

o << "Sensor pose: " << sensorPose << endl;
o << "Pose: " << pose.asString() << endl;
o << "Sensor pose: " << sensorPose << "\n";
o << "Pose: " << pose.asString() << "\n";
o << mrpt::format(
"\n"
"Human-readable pose uncertainty:\n"
"sigma_x = %.03f m\n"
"sigma_y = %.03f m\n"
"sigma_z = %.03f m\n"
"sigma_yaw = %.03f deg\n"
"sigma_pitch = %.03f deg\n"
"sigma_roll = %.03f deg\n",
std::sqrt(pose.cov(0, 0)), std::sqrt(pose.cov(1, 1)),
std::sqrt(pose.cov(2, 2)), mrpt::RAD2DEG(std::sqrt(pose.cov(3, 3))),
mrpt::RAD2DEG(std::sqrt(pose.cov(4, 4))),
mrpt::RAD2DEG(std::sqrt(pose.cov(5, 5))));
}

// See base class docs:
48 changes: 0 additions & 48 deletions libs/obs/src/gnss_messages_common.cpp
Original file line number Diff line number Diff line change
@@ -127,54 +127,6 @@ gnss_message* gnss_message::readAndBuildFromStream(
return msg;
}

// Ctor (default: nullptr pointer)
gnss_message_ptr::gnss_message_ptr() = default;
// Ctor:Makes a copy of the pointee
gnss_message_ptr::gnss_message_ptr(const gnss_message_ptr& o)
{
if (!o.ptr) { ptr = nullptr; }
else
{
mrpt::io::CMemoryStream buf;
auto arch = mrpt::serialization::archiveFrom(buf);
o->writeToStream(arch);
buf.Seek(0);
ptr = gnss_message::readAndBuildFromStream(arch);
}
}
/** Assigns a pointer */
gnss_message_ptr::gnss_message_ptr(const gnss_message* p)
: ptr(const_cast<gnss_message*>(p))
{
}
void gnss_message_ptr::set(gnss_message* p)
{
if (ptr)
{
delete ptr;
ptr = nullptr;
}
ptr = p;
}
// Makes a copy of the pointee
gnss_message_ptr& gnss_message_ptr::operator=(const gnss_message_ptr& o)
{
mrpt::io::CMemoryStream buf;
auto arch = mrpt::serialization::archiveFrom(buf);
o->writeToStream(arch);
buf.Seek(0);
ptr = gnss_message::readAndBuildFromStream(arch);
return *this;
}
gnss_message_ptr::~gnss_message_ptr()
{
if (ptr)
{
delete ptr;
ptr = nullptr;
}
}

// ---------------------------------------
UTC_time::UTC_time() = default;
void UTC_time::writeToStream(mrpt::serialization::CArchive& out) const
6 changes: 2 additions & 4 deletions libs/ros1bridge/include/mrpt/ros1bridge/gps.h
Original file line number Diff line number Diff line change
@@ -40,10 +40,8 @@ bool fromROS(
* The user must supply the "msg_header" field to be copied into the output
* message object, since that part does not appear in MRPT classes.
*
* Since COnservationGPS does not contain "position_covariance" and
* "position_covariance_type" sensor_msgs::NavSatFix::position_covariance_type
* and sensor_msgs::NavSatFix::position_covariance will be empty. \return true
* on sucessful conversion, false on any error.
* \return true on sucessful conversion, only if the input observation has a GGA
* message.
*/
bool toROS(
const mrpt::obs::CObservationGPS& obj, const std_msgs::Header& msg_header,
38 changes: 35 additions & 3 deletions libs/ros1bridge/src/gps.cpp
Original file line number Diff line number Diff line change
@@ -14,6 +14,7 @@
---------------------------------------------------------------*/

#include <mrpt/ros1bridge/gps.h>
#include <mrpt/ros1bridge/time.h>

bool mrpt::ros1bridge::fromROS(
const sensor_msgs::NavSatFix& msg, mrpt::obs::CObservationGPS& obj)
@@ -32,13 +33,27 @@ bool mrpt::ros1bridge::fromROS(
default: gga.fields.fix_quality = 0; // never going to execute default
}
obj.setMsg(gga);

obj.timestamp = mrpt::ros1bridge::fromROS(msg.header.stamp);

if (msg.position_covariance_type !=
sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN)
{
auto& cov = obj.covariance_enu.emplace();
for (int r = 0, i = 0; r < 3; r++)
for (int c = 0; c < 3; c++)
cov(r, c) = msg.position_covariance.at(i++);
}

return true;
}

bool mrpt::ros1bridge::toROS(
const mrpt::obs::CObservationGPS& obj, const std_msgs::Header& msg_header,
sensor_msgs::NavSatFix& msg)
{
bool valid = false;

// 1) sensor_msgs::NavSatFix:: header
msg.header = msg_header;

@@ -69,10 +84,27 @@ bool mrpt::ros1bridge::toROS(
// this might be incorrect as there is not matching field in mrpt
// message type
msg.status.service = 1;

valid = true;
}
/// position_covariance is not available in mrpt
/// position_covariance type is not available in mrpt
return true;

// cov:
if (obj.covariance_enu.has_value())
{
msg.position_covariance_type =
sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN;

for (int r = 0, i = 0; r < 3; r++)
for (int c = 0; c < 3; c++)
msg.position_covariance.at(i++) = (*obj.covariance_enu)(r, c);
}
else
{
msg.position_covariance_type =
sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
}

return valid;
}

/// NavSatFix ROS message
8 changes: 6 additions & 2 deletions libs/ros1bridge/src/image.cpp
Original file line number Diff line number Diff line change
@@ -43,11 +43,15 @@ sensor_msgs::Image mrpt::ros1bridge::toROS(
cv_bridge::CvImage img_bridge;

sensor_msgs::Image msg;
img_bridge = CvImage(msg.header, sensor_msgs::image_encodings::BGR8, cvImg);
img_bridge = CvImage(
msg.header,
i.isColor() ? sensor_msgs::image_encodings::BGR8
: sensor_msgs::image_encodings::MONO8,
cvImg);

img_bridge.toImageMsg(msg);

msg.encoding = "bgr8";
msg.encoding = i.isColor() ? "bgr8" : "mono8";
msg.header = msg_header;
msg.height = i.getHeight();
msg.width = i.getWidth();
6 changes: 2 additions & 4 deletions libs/ros2bridge/include/mrpt/ros2bridge/gps.h
Original file line number Diff line number Diff line change
@@ -41,10 +41,8 @@ bool fromROS(
* The user must supply the "msg_header" field to be copied into the output
* message object, since that part does not appear in MRPT classes.
*
* Since COnservationGPS does not contain "position_covariance" and
* "position_covariance_type" sensor_msgs::NavSatFix::position_covariance_type
* and sensor_msgs::NavSatFix::position_covariance will be empty. \return true
* on sucessful conversion, false on any error.
* \return true on sucessful conversion, only if the input observation has a GGA
* message.
*/
bool toROS(
const mrpt::obs::CObservationGPS& obj,
38 changes: 35 additions & 3 deletions libs/ros2bridge/src/gps.cpp
Original file line number Diff line number Diff line change
@@ -14,6 +14,7 @@
---------------------------------------------------------------*/

#include <mrpt/ros2bridge/gps.h>
#include <mrpt/ros2bridge/time.h>

bool mrpt::ros2bridge::fromROS(
const sensor_msgs::msg::NavSatFix& msg, mrpt::obs::CObservationGPS& obj)
@@ -32,13 +33,27 @@ bool mrpt::ros2bridge::fromROS(
default: gga.fields.fix_quality = 0; // never going to execute default
}
obj.setMsg(gga);

obj.timestamp = mrpt::ros2bridge::fromROS(msg.header.stamp);

if (msg.position_covariance_type !=
sensor_msgs::msg::NavSatFix::COVARIANCE_TYPE_UNKNOWN)
{
auto& cov = obj.covariance_enu.emplace();
for (int r = 0, i = 0; r < 3; r++)
for (int c = 0; c < 3; c++)
cov(r, c) = msg.position_covariance.at(i++);
}

return true;
}

bool mrpt::ros2bridge::toROS(
const mrpt::obs::CObservationGPS& obj,
const std_msgs::msg::Header& msg_header, sensor_msgs::msg::NavSatFix& msg)
{
bool valid = false;

// 1) sensor_msgs::NavSatFix:: header
msg.header = msg_header;

@@ -69,10 +84,27 @@ bool mrpt::ros2bridge::toROS(
// this might be incorrect as there is not matching field in mrpt
// message type
msg.status.service = 1;

valid = true;
}
/// position_covariance is not available in mrpt
/// position_covariance type is not available in mrpt
return true;

// cov:
if (obj.covariance_enu.has_value())
{
msg.position_covariance_type =
sensor_msgs::msg::NavSatFix::COVARIANCE_TYPE_KNOWN;

for (int r = 0, i = 0; r < 3; r++)
for (int c = 0; c < 3; c++)
msg.position_covariance.at(i++) = (*obj.covariance_enu)(r, c);
}
else
{
msg.position_covariance_type =
sensor_msgs::msg::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
}

return valid;
}

/// NavSatFix ROS message
8 changes: 6 additions & 2 deletions libs/ros2bridge/src/image.cpp
Original file line number Diff line number Diff line change
@@ -43,11 +43,15 @@ sensor_msgs::msg::Image mrpt::ros2bridge::toROS(
cv_bridge::CvImage img_bridge;

sensor_msgs::msg::Image msg;
img_bridge = CvImage(msg.header, sensor_msgs::image_encodings::BGR8, cvImg);
img_bridge = CvImage(
msg.header,
i.isColor() ? sensor_msgs::image_encodings::BGR8
: sensor_msgs::image_encodings::MONO8,
cvImg);

img_bridge.toImageMsg(msg);

msg.encoding = "bgr8";
msg.encoding = i.isColor() ? "bgr8" : "mono8";
msg.header = msg_header;
msg.height = i.getHeight();
msg.width = i.getWidth();
4 changes: 2 additions & 2 deletions libs/topography/src/path_from_rtk_gps.cpp
Original file line number Diff line number Diff line change
@@ -61,8 +61,8 @@ void mrpt::topography::path_from_rtk_gps(
TPathFromRTKInfo outInfoTemp;
if (outInfo) *outInfo = outInfoTemp;

map<string, map<Clock::time_point, TPoint3D>>
gps_paths; // label -> (time -> 3D local coords)
// label -> (time -> 3D local coords)
map<string, map<Clock::time_point, TPoint3D>> gps_paths;

bool abort = false;
bool ref_valid = false;
18 changes: 8 additions & 10 deletions libs/topography/src/path_from_rtk_gps_unittest.cpp
Original file line number Diff line number Diff line change
@@ -56,19 +56,17 @@ TEST(TopographyReconstructPathFrom3RTK, sampleDataset)

EXPECT_EQ(robot_path.size(), 75u);

// clang-format off
// Expected values:
// 1226225355.000000 279.705647 216.651473 8.517821 0.194222 -0.083873
// -0.045293
// 1226225380.000000 377.095830 233.343569 9.724171 0.177037 -0.073565
// -0.019024
const mrpt::Clock::time_point t1(
std::chrono::seconds(1226225355 + 11644473600));
const mrpt::Clock::time_point t2(
std::chrono::seconds(1226225380 + 11644473600));
// 1226225355.000000 279.696222 216.622980 9.213152 0.195764 -0.031973 -0.042048
// 1226225380.000000 377.086918 233.311009 10.474043 0.178932 -0.025085 -0.013734
// clang-format on
const auto t1 = mrpt::Clock::fromDouble(1226225355.0);
const auto t2 = mrpt::Clock::fromDouble(1226225380.0);
const CPose3D pose_GT_1(
279.696, 216.623, 9.21315, 0.195764, -0.0319733, -0.0420478);
279.696222, 216.622980, 9.213152, 0.195764, -0.031973, -0.042048);
const CPose3D pose_GT_2(
377.087, 233.311, 10.474, 0.178932, -0.0212096, -0.0154982);
377.086918, 233.311009, 10.474043, 0.178932, -0.025085, -0.013734);

CPose3D pose1, pose2;
bool valid;
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -7,7 +7,7 @@
<package format="3">
<name>mrpt2</name>
<!-- Before updating version number, read [MRPT_ROOT]/version_prefix.txt first -->
<version>2.11.11</version>
<version>2.11.12</version>
<description>Mobile Robot Programming Toolkit (MRPT) version 2.x</description>

<author email="joseluisblancoc@gmail.com">Jose-Luis Blanco-Claraco</author>
1 change: 0 additions & 1 deletion python/all_mrpt_obs.cpp
Original file line number Diff line number Diff line change
@@ -5,7 +5,6 @@
#include "src/mrpt/obs/CObservation2DRangeScan.cpp"
#include "src/mrpt/obs/CObservation2DRangeScanWithUncertainty.cpp"
#include "src/mrpt/obs/CObservation3DRangeScan.cpp"
#include "src/mrpt/obs/CObservationBatteryState.cpp"
#include "src/mrpt/obs/CObservationCANBusJ1939.cpp"
#include "src/mrpt/obs/CObservation.cpp"
#include "src/mrpt/obs/CObservationGasSensors.cpp"
3 changes: 2 additions & 1 deletion python/all_mrpt_obs2.cpp
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
#include "src/mrpt/obs/CObservationGPS.cpp"
#include "src/mrpt/obs/CObservationImage.cpp"
#include "src/mrpt/obs/CObservationIMU.cpp"
#include "src/mrpt/obs/CObservationOdometry.cpp"
#include "src/mrpt/obs/CObservationPointCloud.cpp"
#include "src/mrpt/obs/CObservationRange.cpp"
#include "src/mrpt/obs/CObservationRawDAQ.cpp"
#include "src/mrpt/obs/CObservationRFID.cpp"
#include "src/mrpt/obs/CObservationRGBD360.cpp"
#include "src/mrpt/obs/CObservationSkeleton.cpp"
#include "src/mrpt/obs/CObservationStereoImages.cpp"
#include "src/mrpt/obs/CObservation3DScene.cpp"
#include "src/mrpt/obs/CObservationBearingRange.cpp"
2 changes: 1 addition & 1 deletion python/all_mrpt_obs3.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
#include "src/mrpt/obs/CObservationWindSensor.cpp"
#include "src/mrpt/obs/CObservationWirelessPower.cpp"
#include "src/mrpt/obs/CRawlog.cpp"
#include "src/mrpt/obs/CSensoryFrame.cpp"
#include "src/mrpt/obs/customizable_obs_viz.cpp"
#include "src/mrpt/obs/format_externals_filename.cpp"
@@ -10,3 +9,4 @@
#include "src/mrpt/obs/T3DPointsProjectionParams.cpp"
#include "src/mrpt/obs/TPixelLabelInfo.cpp"
#include "src/mrpt/obs/VelodyneCalibration.cpp"
#include "src/mrpt/obs/CObservationRobotPose.cpp"
1 change: 1 addition & 0 deletions python/all_mrpt_typemeta.cpp
Original file line number Diff line number Diff line change
@@ -5,4 +5,5 @@
#include "src/mrpt/typemeta/TEnumType_4.cpp"
#include "src/mrpt/typemeta/TEnumType_5.cpp"
#include "src/mrpt/typemeta/TEnumType_6.cpp"
#include "src/mrpt/typemeta/TEnumType_7.cpp"
#include "src/mrpt/typemeta/TEnumType.cpp"
1 change: 0 additions & 1 deletion python/all_unknown.cpp
Original file line number Diff line number Diff line change
@@ -5,5 +5,4 @@
#include "src/unknown/unknown_5.cpp"
#include "src/unknown/unknown_6.cpp"
#include "src/unknown/unknown_7.cpp"
#include "src/unknown/unknown_8.cpp"
#include "src/unknown/unknown.cpp"
88 changes: 0 additions & 88 deletions python/src/mrpt/math/MatrixBase.cpp

This file was deleted.

475 changes: 4 additions & 471 deletions python/src/mrpt/obs/CActionRobotMovement3D.cpp

Large diffs are not rendered by default.

Large diffs are not rendered by default.

Large diffs are not rendered by default.

7 changes: 4 additions & 3 deletions python/src/mrpt/obs/CObservationGPS.cpp
Original file line number Diff line number Diff line change
@@ -242,22 +242,23 @@ struct PyCallBack_mrpt_obs_CObservationGPS : public mrpt::obs::CObservationGPS {
void bind_mrpt_obs_CObservationGPS(std::function< pybind11::module &(std::string const &namespace_) > &M)
{
{ // mrpt::obs::CObservationGPS file:mrpt/obs/CObservationGPS.h line:68
pybind11::class_<mrpt::obs::CObservationGPS, std::shared_ptr<mrpt::obs::CObservationGPS>, PyCallBack_mrpt_obs_CObservationGPS, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationGPS", "This class stores messages from GNSS or GNSS+IMU devices, from\n consumer-grade inexpensive GPS receivers to Novatel/Topcon/... advanced RTK\n solutions.\n\n See mrpt::hwdrivers::CGPSInterface for a class capable of reading from a\n serial port or any input stream and the ASCII/binary stream into\n indivual messages in mrpt::obs::CObservationGPS objects.\n\n Supported message types are:\n - NMEA 0183 (ASCII): GGA, RMC\n - Topcon GRIL (Binary): PZS, SATS\n - Novatel GNSS/SPAN OEM6 (Binary): See list of log packets under namespace\n mrpt::obs::gnss and in enum type mrpt::obs::gnss::gnss_message_type_t\n\n Note that this object has timestamp fields:\n - The standard CObservation::timestamp field in the base class, which should\n contain the accurate satellite-based UTC timestamp, and\n - the field CObservationGPS::originalReceivedTimestamp, with the local\n computer-based timestamp based on the reception of the message in the\n computer.\n\n Normally, users read and write messages by means of these methods:\n - CObservationGPS::getMsgByClass()\n - CObservationGPS::setMsg()\n - CObservationGPS::hasMsgType()\n - CObservationGPS::hasMsgClass()\n\n Example access to GPS datum:\n \n\n\n\n\n\n\n\n\n\n \n [API changed in MRPT 1.4.0] mrpt::obs::CObservationGPS now\n stores message objects in a more flexible way. API clean-up and extended so\n the number of GNSS message types is larger and more scalable.\n \n\n Porting old code: For example, replace `observation.GGA_datum.XXX` with\n `observation.getMsgByClass<gnss::Message_NMEA_GGA>().fields.XXX`, etc.\n \n\n CObservation\n \n\n\n ");
cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationGPS(); }, [](){ return new PyCallBack_mrpt_obs_CObservationGPS(); } ) );
pybind11::class_<mrpt::obs::CObservationGPS, std::shared_ptr<mrpt::obs::CObservationGPS>, PyCallBack_mrpt_obs_CObservationGPS, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationGPS", "This class stores messages from GNSS or GNSS+IMU devices, from\n consumer-grade inexpensive GPS receivers to Novatel/Topcon/... advanced RTK\n solutions.\n\n See mrpt::hwdrivers::CGPSInterface for a class capable of reading from a\n serial port or any input stream and the ASCII/binary stream into\n indivual messages in mrpt::obs::CObservationGPS objects.\n\n Supported message types are:\n - NMEA 0183 (ASCII): GGA, RMC, etc.\n - Topcon GRIL (Binary): PZS, SATS\n - Novatel GNSS/SPAN OEM6 (Binary): See list of log packets under namespace\n mrpt::obs::gnss and in enum type mrpt::obs::gnss::gnss_message_type_t\n\n Note that this object has timestamp fields:\n - The standard CObservation::timestamp field in the base class, which should\n contain the accurate satellite-based UTC timestamp, and\n - the field CObservationGPS::originalReceivedTimestamp, with the local\n computer-based timestamp based on the reception of the message in the\n computer.\n\n Normally, users read and write messages by means of these methods:\n - CObservationGPS::getMsgByClass()\n - CObservationGPS::setMsg()\n - CObservationGPS::hasMsgType()\n - CObservationGPS::hasMsgClass()\n\n Example access to GPS datum:\n \n\n\n\n\n\n\n\n\n\n \n Since MRPT 2.11.12 there is an optional field for ENU covariance for\n easier compatibility with ROS messages.\n\n \n CObservation\n \n\n\n ");
cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservationGPS const &o){ return new PyCallBack_mrpt_obs_CObservationGPS(o); } ) );
cl.def( pybind11::init( [](mrpt::obs::CObservationGPS const &o){ return new mrpt::obs::CObservationGPS(o); } ) );
cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationGPS(); }, [](){ return new PyCallBack_mrpt_obs_CObservationGPS(); } ) );
cl.def_readwrite("sensorPose", &mrpt::obs::CObservationGPS::sensorPose);
cl.def_readwrite("originalReceivedTimestamp", &mrpt::obs::CObservationGPS::originalReceivedTimestamp);
cl.def_readwrite("has_satellite_timestamp", &mrpt::obs::CObservationGPS::has_satellite_timestamp);
cl.def_readwrite("messages", &mrpt::obs::CObservationGPS::messages);
cl.def_readwrite("covariance_enu", &mrpt::obs::CObservationGPS::covariance_enu);
cl.def_static("Create", (class std::shared_ptr<class mrpt::obs::CObservationGPS> (*)()) &mrpt::obs::CObservationGPS::Create, "C++: mrpt::obs::CObservationGPS::Create() --> class std::shared_ptr<class mrpt::obs::CObservationGPS>");
cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservationGPS::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservationGPS::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic);
cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservationGPS::*)() const) &mrpt::obs::CObservationGPS::GetRuntimeClass, "C++: mrpt::obs::CObservationGPS::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic);
cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservationGPS::*)() const) &mrpt::obs::CObservationGPS::clone, "C++: mrpt::obs::CObservationGPS::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic);
cl.def_static("CreateObject", (class std::shared_ptr<class mrpt::rtti::CObject> (*)()) &mrpt::obs::CObservationGPS::CreateObject, "C++: mrpt::obs::CObservationGPS::CreateObject() --> class std::shared_ptr<class mrpt::rtti::CObject>");
cl.def("hasMsgType", (bool (mrpt::obs::CObservationGPS::*)(const enum mrpt::obs::gnss::gnss_message_type_t) const) &mrpt::obs::CObservationGPS::hasMsgType, "Returns true if the list contains one of\n the requested type. \n\n mrpt::obs::gnss::gnss_message_type_t,\n CObservationGPS::getMsgByType() \n\nC++: mrpt::obs::CObservationGPS::hasMsgType(const enum mrpt::obs::gnss::gnss_message_type_t) const --> bool", pybind11::arg("type_id"));
cl.def("getMsgByType", (struct mrpt::obs::gnss::gnss_message * (mrpt::obs::CObservationGPS::*)(const enum mrpt::obs::gnss::gnss_message_type_t)) &mrpt::obs::CObservationGPS::getMsgByType, "Returns a pointer to the message in the list CObservationGPS::messages\n of the requested type. Users normally would prefer using\n CObservationGPS::getMsgByClass()\n to avoid having to perform a dynamic_cast<>() on the returned pointer.\n \n\n std::runtime_error If there is no such a message in the list.\n Please, check existence before calling this method with\n CObservationGPS::hasMsgType()\n \n\n mrpt::obs::gnss::gnss_message_type_t,\n CObservationGPS::getMsgByClass(), CObservationGPS::hasMsgType() \n\nC++: mrpt::obs::CObservationGPS::getMsgByType(const enum mrpt::obs::gnss::gnss_message_type_t) --> struct mrpt::obs::gnss::gnss_message *", pybind11::return_value_policy::automatic, pybind11::arg("type_id"));
cl.def("clear", (void (mrpt::obs::CObservationGPS::*)()) &mrpt::obs::CObservationGPS::clear, "Empties this observation, clearing the container \n\nC++: mrpt::obs::CObservationGPS::clear() --> void");
cl.def("swap", (void (mrpt::obs::CObservationGPS::*)(class mrpt::obs::CObservationGPS &)) &mrpt::obs::CObservationGPS::swap, "C++: mrpt::obs::CObservationGPS::swap(class mrpt::obs::CObservationGPS &) --> void", pybind11::arg("o"));
cl.def("getSensorPose", (void (mrpt::obs::CObservationGPS::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationGPS::getSensorPose, "C++: mrpt::obs::CObservationGPS::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose"));
cl.def("setSensorPose", (void (mrpt::obs::CObservationGPS::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationGPS::setSensorPose, "C++: mrpt::obs::CObservationGPS::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose"));
cl.def("getOriginalReceivedTimeStamp", (mrpt::Clock::time_point (mrpt::obs::CObservationGPS::*)() const) &mrpt::obs::CObservationGPS::getOriginalReceivedTimeStamp, "C++: mrpt::obs::CObservationGPS::getOriginalReceivedTimeStamp() const --> mrpt::Clock::time_point");
629 changes: 629 additions & 0 deletions python/src/mrpt/obs/CObservationRobotPose.cpp

Large diffs are not rendered by default.

176 changes: 0 additions & 176 deletions python/src/mrpt/obs/CRawlog.cpp

This file was deleted.

157 changes: 141 additions & 16 deletions python/src/mrpt/obs/gnss_messages_type_list.cpp
Original file line number Diff line number Diff line change
@@ -74,6 +74,96 @@ struct PyCallBack_mrpt_obs_gnss_Message_NMEA_GGA : public mrpt::obs::gnss::Messa
}
};

// mrpt::obs::gnss::Message_NMEA_GLL file: line:104
struct PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL : public mrpt::obs::gnss::Message_NMEA_GLL {
using mrpt::obs::gnss::Message_NMEA_GLL::Message_NMEA_GLL;

void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::obs::gnss::Message_NMEA_GLL *>(this), "internal_writeToStream");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>(a0);
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return Message_NMEA_GLL::internal_writeToStream(a0);
}
void internal_readFromStream(class mrpt::serialization::CArchive & a0) override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::obs::gnss::Message_NMEA_GLL *>(this), "internal_readFromStream");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>(a0);
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return Message_NMEA_GLL::internal_readFromStream(a0);
}
void fixEndianness() override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::obs::gnss::Message_NMEA_GLL *>(this), "fixEndianness");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return gnss_message::fixEndianness();
}
};

// mrpt::obs::gnss::Message_NMEA_RMC file: line:133
struct PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC : public mrpt::obs::gnss::Message_NMEA_RMC {
using mrpt::obs::gnss::Message_NMEA_RMC::Message_NMEA_RMC;

void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::obs::gnss::Message_NMEA_RMC *>(this), "internal_writeToStream");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>(a0);
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return Message_NMEA_RMC::internal_writeToStream(a0);
}
void internal_readFromStream(class mrpt::serialization::CArchive & a0) override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::obs::gnss::Message_NMEA_RMC *>(this), "internal_readFromStream");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>(a0);
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return Message_NMEA_RMC::internal_readFromStream(a0);
}
void fixEndianness() override {
pybind11::gil_scoped_acquire gil;
pybind11::function overload = pybind11::get_overload(static_cast<const mrpt::obs::gnss::Message_NMEA_RMC *>(this), "fixEndianness");
if (overload) {
auto o = overload.operator()<pybind11::return_value_policy::reference>();
if (pybind11::detail::cast_is_temporary_value_reference<void>::value) {
static pybind11::detail::override_caster_t<void> caster;
return pybind11::detail::cast_ref<void>(std::move(o), caster);
}
else return pybind11::detail::cast_safe<void>(std::move(o));
}
return gnss_message::fixEndianness();
}
};

void bind_mrpt_obs_gnss_messages_type_list(std::function< pybind11::module &(std::string const &namespace_) > &M)
{
// mrpt::obs::gnss::gnss_message_type_t file:mrpt/obs/gnss_messages_type_list.h line:22
@@ -141,22 +231,7 @@ void bind_mrpt_obs_gnss_messages_type_list(std::function< pybind11::module &(std
cl.def("getMessageTypeAsString", (const std::string & (mrpt::obs::gnss::gnss_message::*)() const) &mrpt::obs::gnss::gnss_message::getMessageTypeAsString, "Returns \"NMEA_GGA\", etc. \n\nC++: mrpt::obs::gnss::gnss_message::getMessageTypeAsString() const --> const std::string &", pybind11::return_value_policy::automatic);
cl.def("assign", (struct mrpt::obs::gnss::gnss_message & (mrpt::obs::gnss::gnss_message::*)(const struct mrpt::obs::gnss::gnss_message &)) &mrpt::obs::gnss::gnss_message::operator=, "C++: mrpt::obs::gnss::gnss_message::operator=(const struct mrpt::obs::gnss::gnss_message &) --> struct mrpt::obs::gnss::gnss_message &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
{ // mrpt::obs::gnss::gnss_message_ptr file: line:100
pybind11::class_<mrpt::obs::gnss::gnss_message_ptr, std::shared_ptr<mrpt::obs::gnss::gnss_message_ptr>> cl(M("mrpt::obs::gnss"), "gnss_message_ptr", "A smart pointer to a GNSS message. \n gnss_message,\n mrpt::obs::CObservationGPS ");
cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::gnss_message_ptr(); } ) );
cl.def( pybind11::init( [](mrpt::obs::gnss::gnss_message_ptr const &o){ return new mrpt::obs::gnss::gnss_message_ptr(o); } ) );
cl.def( pybind11::init<const struct mrpt::obs::gnss::gnss_message *>(), pybind11::arg("p") );

cl.def("assign", (struct mrpt::obs::gnss::gnss_message_ptr & (mrpt::obs::gnss::gnss_message_ptr::*)(const struct mrpt::obs::gnss::gnss_message_ptr &)) &mrpt::obs::gnss::gnss_message_ptr::operator=, "C++: mrpt::obs::gnss::gnss_message_ptr::operator=(const struct mrpt::obs::gnss::gnss_message_ptr &) --> struct mrpt::obs::gnss::gnss_message_ptr &", pybind11::return_value_policy::automatic, pybind11::arg("o"));
cl.def("__eq__", (bool (mrpt::obs::gnss::gnss_message_ptr::*)(const struct mrpt::obs::gnss::gnss_message *) const) &mrpt::obs::gnss::gnss_message_ptr::operator==, "C++: mrpt::obs::gnss::gnss_message_ptr::operator==(const struct mrpt::obs::gnss::gnss_message *) const --> bool", pybind11::arg("o"));
cl.def("__eq__", (bool (mrpt::obs::gnss::gnss_message_ptr::*)(const struct mrpt::obs::gnss::gnss_message_ptr &) const) &mrpt::obs::gnss::gnss_message_ptr::operator==, "C++: mrpt::obs::gnss::gnss_message_ptr::operator==(const struct mrpt::obs::gnss::gnss_message_ptr &) const --> bool", pybind11::arg("o"));
cl.def("__ne__", (bool (mrpt::obs::gnss::gnss_message_ptr::*)(const struct mrpt::obs::gnss::gnss_message *) const) &mrpt::obs::gnss::gnss_message_ptr::operator!=, "C++: mrpt::obs::gnss::gnss_message_ptr::operator!=(const struct mrpt::obs::gnss::gnss_message *) const --> bool", pybind11::arg("o"));
cl.def("__ne__", (bool (mrpt::obs::gnss::gnss_message_ptr::*)(const struct mrpt::obs::gnss::gnss_message_ptr &) const) &mrpt::obs::gnss::gnss_message_ptr::operator!=, "C++: mrpt::obs::gnss::gnss_message_ptr::operator!=(const struct mrpt::obs::gnss::gnss_message_ptr &) const --> bool", pybind11::arg("o"));
cl.def("get", (struct mrpt::obs::gnss::gnss_message *& (mrpt::obs::gnss::gnss_message_ptr::*)()) &mrpt::obs::gnss::gnss_message_ptr::get, "C++: mrpt::obs::gnss::gnss_message_ptr::get() --> struct mrpt::obs::gnss::gnss_message *&", pybind11::return_value_policy::automatic);
cl.def("arrow", (struct mrpt::obs::gnss::gnss_message *& (mrpt::obs::gnss::gnss_message_ptr::*)()) &mrpt::obs::gnss::gnss_message_ptr::operator->, "C++: mrpt::obs::gnss::gnss_message_ptr::operator->() --> struct mrpt::obs::gnss::gnss_message *&", pybind11::return_value_policy::automatic);
cl.def("set", (void (mrpt::obs::gnss::gnss_message_ptr::*)(struct mrpt::obs::gnss::gnss_message *)) &mrpt::obs::gnss::gnss_message_ptr::set, "Replaces the pointee with a new pointer. Its memory now belongs to this\n object, do not free manually. \n\nC++: mrpt::obs::gnss::gnss_message_ptr::set(struct mrpt::obs::gnss::gnss_message *) --> void", pybind11::arg("p"));
}
{ // mrpt::obs::gnss::UTC_time file: line:194
{ // mrpt::obs::gnss::UTC_time file: line:159
pybind11::class_<mrpt::obs::gnss::UTC_time, std::shared_ptr<mrpt::obs::gnss::UTC_time>> cl(M("mrpt::obs::gnss"), "UTC_time", "UTC (Coordinated Universal Time) time-stamp structure for GPS messages. \n\n mrpt::obs::CObservationGPS ");
cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::UTC_time(); } ) );
cl.def( pybind11::init( [](mrpt::obs::gnss::UTC_time const &o){ return new mrpt::obs::gnss::UTC_time(o); } ) );
@@ -198,4 +273,54 @@ void bind_mrpt_obs_gnss_messages_type_list(std::function< pybind11::module &(std
}

}
{ // mrpt::obs::gnss::Message_NMEA_GLL file: line:104
pybind11::class_<mrpt::obs::gnss::Message_NMEA_GLL, std::shared_ptr<mrpt::obs::gnss::Message_NMEA_GLL>, PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NMEA_GLL", "NMEA datum: GLL. \n mrpt::obs::CObservationGPS ");
cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_GLL(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL(); } ) );
cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL(o); } ) );
cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_GLL const &o){ return new mrpt::obs::gnss::Message_NMEA_GLL(o); } ) );
cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NMEA_GLL::fields);
cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_GLL & (mrpt::obs::gnss::Message_NMEA_GLL::*)(const struct mrpt::obs::gnss::Message_NMEA_GLL &)) &mrpt::obs::gnss::Message_NMEA_GLL::operator=, "C++: mrpt::obs::gnss::Message_NMEA_GLL::operator=(const struct mrpt::obs::gnss::Message_NMEA_GLL &) --> struct mrpt::obs::gnss::Message_NMEA_GLL &", pybind11::return_value_policy::automatic, pybind11::arg(""));

{ // mrpt::obs::gnss::Message_NMEA_GLL::content_t file: line:113
auto & enclosing_class = cl;
pybind11::class_<mrpt::obs::gnss::Message_NMEA_GLL::content_t, std::shared_ptr<mrpt::obs::gnss::Message_NMEA_GLL::content_t>> cl(enclosing_class, "content_t", "");
cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_GLL::content_t(); } ) );
cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_GLL::content_t const &o){ return new mrpt::obs::gnss::Message_NMEA_GLL::content_t(o); } ) );
cl.def_readwrite("UTCTime", &mrpt::obs::gnss::Message_NMEA_GLL::content_t::UTCTime);
cl.def_readwrite("latitude_degrees", &mrpt::obs::gnss::Message_NMEA_GLL::content_t::latitude_degrees);
cl.def_readwrite("longitude_degrees", &mrpt::obs::gnss::Message_NMEA_GLL::content_t::longitude_degrees);
cl.def_readwrite("validity_char", &mrpt::obs::gnss::Message_NMEA_GLL::content_t::validity_char);
cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_GLL::content_t & (mrpt::obs::gnss::Message_NMEA_GLL::content_t::*)(const struct mrpt::obs::gnss::Message_NMEA_GLL::content_t &)) &mrpt::obs::gnss::Message_NMEA_GLL::content_t::operator=, "C++: mrpt::obs::gnss::Message_NMEA_GLL::content_t::operator=(const struct mrpt::obs::gnss::Message_NMEA_GLL::content_t &) --> struct mrpt::obs::gnss::Message_NMEA_GLL::content_t &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}

}
{ // mrpt::obs::gnss::Message_NMEA_RMC file: line:133
pybind11::class_<mrpt::obs::gnss::Message_NMEA_RMC, std::shared_ptr<mrpt::obs::gnss::Message_NMEA_RMC>, PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NMEA_RMC", "NMEA datum: RMC. \n mrpt::obs::CObservationGPS ");
cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_RMC(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC(); } ) );
cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC(o); } ) );
cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_RMC const &o){ return new mrpt::obs::gnss::Message_NMEA_RMC(o); } ) );
cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NMEA_RMC::fields);
cl.def("getDateAsTimestamp", (mrpt::Clock::time_point (mrpt::obs::gnss::Message_NMEA_RMC::*)() const) &mrpt::obs::gnss::Message_NMEA_RMC::getDateAsTimestamp, "Build an MRPT timestamp with the year/month/day of this observation. \n\nC++: mrpt::obs::gnss::Message_NMEA_RMC::getDateAsTimestamp() const --> mrpt::Clock::time_point");
cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_RMC & (mrpt::obs::gnss::Message_NMEA_RMC::*)(const struct mrpt::obs::gnss::Message_NMEA_RMC &)) &mrpt::obs::gnss::Message_NMEA_RMC::operator=, "C++: mrpt::obs::gnss::Message_NMEA_RMC::operator=(const struct mrpt::obs::gnss::Message_NMEA_RMC &) --> struct mrpt::obs::gnss::Message_NMEA_RMC &", pybind11::return_value_policy::automatic, pybind11::arg(""));

{ // mrpt::obs::gnss::Message_NMEA_RMC::content_t file: line:142
auto & enclosing_class = cl;
pybind11::class_<mrpt::obs::gnss::Message_NMEA_RMC::content_t, std::shared_ptr<mrpt::obs::gnss::Message_NMEA_RMC::content_t>> cl(enclosing_class, "content_t", "");
cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_RMC::content_t(); } ) );
cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_RMC::content_t const &o){ return new mrpt::obs::gnss::Message_NMEA_RMC::content_t(o); } ) );
cl.def_readwrite("UTCTime", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::UTCTime);
cl.def_readwrite("validity_char", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::validity_char);
cl.def_readwrite("latitude_degrees", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::latitude_degrees);
cl.def_readwrite("longitude_degrees", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::longitude_degrees);
cl.def_readwrite("speed_knots", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::speed_knots);
cl.def_readwrite("direction_degrees", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::direction_degrees);
cl.def_readwrite("date_day", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::date_day);
cl.def_readwrite("date_month", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::date_month);
cl.def_readwrite("date_year", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::date_year);
cl.def_readwrite("magnetic_dir", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::magnetic_dir);
cl.def_readwrite("positioning_mode", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::positioning_mode);
cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_RMC::content_t & (mrpt::obs::gnss::Message_NMEA_RMC::content_t::*)(const struct mrpt::obs::gnss::Message_NMEA_RMC::content_t &)) &mrpt::obs::gnss::Message_NMEA_RMC::content_t::operator=, "C++: mrpt::obs::gnss::Message_NMEA_RMC::content_t::operator=(const struct mrpt::obs::gnss::Message_NMEA_RMC::content_t &) --> struct mrpt::obs::gnss::Message_NMEA_RMC::content_t &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}

}
}
19 changes: 9 additions & 10 deletions python/src/mrpt/typemeta/TEnumType.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#include <iterator>
#include <memory>
#include <mrpt/bayes/CParticleFilter.h>
#include <mrpt/hwdrivers/CGenericSensor.h>
#include <mrpt/obs/CActionRobotMovement2D.h>
#include <mrpt/system/COutputLogger.h>
#include <mrpt/typemeta/TEnumType.h>
@@ -68,14 +67,14 @@ void bind_mrpt_typemeta_TEnumType(std::function< pybind11::module &(std::string
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::obs::CActionRobotMovement2D::TEstimationMethod, std::string > & (mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TEstimationMethod,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::obs::CActionRobotMovement2D::TEstimationMethod, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TEstimationMethod, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TEstimationMethod, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::obs::CActionRobotMovement2D::TEstimationMethod, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::obs::CActionRobotMovement2D::TEstimationMethod, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_hwdrivers_CGenericSensor_TSensorState_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>(); } ) );
cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string> const &o){ return new mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>(o); } ) );
cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>::m_k2v);
cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>::m_v2k);
cl.def("direct", (bool (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>::*)(const enum mrpt::hwdrivers::CGenericSensor::TSensorState &, std::string &) const) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::direct, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::direct(const enum mrpt::hwdrivers::CGenericSensor::TSensorState &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v"));
cl.def("inverse", (bool (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>::*)(const std::string &, enum mrpt::hwdrivers::CGenericSensor::TSensorState &) const) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::inverse, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::inverse(const std::string &, enum mrpt::hwdrivers::CGenericSensor::TSensorState &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k"));
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>::*)(const enum mrpt::hwdrivers::CGenericSensor::TSensorState &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::insert(const enum mrpt::hwdrivers::CGenericSensor::TSensorState &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CGenericSensor::TSensorState, std::string > & (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CGenericSensor::TSensorState, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CGenericSensor::TSensorState, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CGenericSensor::TSensorState, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_obs_CActionRobotMovement2D_TDrawSampleMotionModel_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel,std::string>(); } ) );
cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel,std::string> const &o){ return new mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel,std::string>(o); } ) );
cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel,std::string>::m_k2v);
cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel,std::string>::m_v2k);
cl.def("direct", (bool (mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel,std::string>::*)(const enum mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel &, std::string &) const) &mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel, std::string>::direct, "C++: mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel, std::string>::direct(const enum mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v"));
cl.def("inverse", (bool (mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel,std::string>::*)(const std::string &, enum mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel &) const) &mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel, std::string>::inverse, "C++: mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel, std::string>::inverse(const std::string &, enum mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k"));
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel,std::string>::*)(const enum mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel, std::string>::insert(const enum mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel, std::string > & (mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
}
24 changes: 12 additions & 12 deletions python/src/mrpt/typemeta/TEnumType_1.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
#include <iterator>
#include <memory>
#include <mrpt/hwdrivers/CGenericSensor.h>
#include <mrpt/img/DistortionModel.h>
#include <mrpt/img/color_maps.h>
#include <mrpt/opengl/CRenderizable.h>
#include <mrpt/poses/CPoseInterpolatorBase.h>
#include <mrpt/slam/CICP.h>
#include <mrpt/typemeta/TEnumType.h>
@@ -24,6 +24,17 @@

void bind_mrpt_typemeta_TEnumType_1(std::function< pybind11::module &(std::string const &namespace_) > &M)
{
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_hwdrivers_CGenericSensor_TSensorState_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>(); } ) );
cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string> const &o){ return new mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>(o); } ) );
cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>::m_k2v);
cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>::m_v2k);
cl.def("direct", (bool (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>::*)(const enum mrpt::hwdrivers::CGenericSensor::TSensorState &, std::string &) const) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::direct, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::direct(const enum mrpt::hwdrivers::CGenericSensor::TSensorState &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v"));
cl.def("inverse", (bool (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>::*)(const std::string &, enum mrpt::hwdrivers::CGenericSensor::TSensorState &) const) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::inverse, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::inverse(const std::string &, enum mrpt::hwdrivers::CGenericSensor::TSensorState &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k"));
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>::*)(const enum mrpt::hwdrivers::CGenericSensor::TSensorState &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::insert(const enum mrpt::hwdrivers::CGenericSensor::TSensorState &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CGenericSensor::TSensorState, std::string > & (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CGenericSensor::TSensorState, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGenericSensor::TSensorState, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CGenericSensor::TSensorState, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CGenericSensor::TSensorState, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::poses::TInterpolatorMethod,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::poses::TInterpolatorMethod,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_poses_TInterpolatorMethod_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::poses::TInterpolatorMethod,std::string>(); } ) );
@@ -79,15 +90,4 @@ void bind_mrpt_typemeta_TEnumType_1(std::function< pybind11::module &(std::strin
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::img::DistortionModel,std::string>::*)(const enum mrpt::img::DistortionModel &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::img::DistortionModel, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::img::DistortionModel, std::string>::insert(const enum mrpt::img::DistortionModel &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::img::DistortionModel, std::string > & (mrpt::typemeta::internal::bimap<mrpt::img::DistortionModel,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::img::DistortionModel, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::img::DistortionModel, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::img::DistortionModel, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::img::DistortionModel, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::img::DistortionModel, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_opengl_TCullFace_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>(); } ) );
cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string> const &o){ return new mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>(o); } ) );
cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>::m_k2v);
cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>::m_v2k);
cl.def("direct", (bool (mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>::*)(const enum mrpt::opengl::TCullFace &, std::string &) const) &mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::direct, "C++: mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::direct(const enum mrpt::opengl::TCullFace &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v"));
cl.def("inverse", (bool (mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>::*)(const std::string &, enum mrpt::opengl::TCullFace &) const) &mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::inverse, "C++: mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::inverse(const std::string &, enum mrpt::opengl::TCullFace &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k"));
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>::*)(const enum mrpt::opengl::TCullFace &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::insert(const enum mrpt::opengl::TCullFace &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::opengl::TCullFace, std::string > & (mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::opengl::TCullFace, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::opengl::TCullFace, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::opengl::TCullFace, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
}
24 changes: 12 additions & 12 deletions python/src/mrpt/typemeta/TEnumType_2.cpp
Original file line number Diff line number Diff line change
@@ -3,8 +3,8 @@
#include <mrpt/hwdrivers/CGPSInterface.h>
#include <mrpt/hwdrivers/CImageGrabber_OpenCV.h>
#include <mrpt/hwdrivers/CKinect.h>
#include <mrpt/hwdrivers/CVelodyneScanner.h>
#include <mrpt/obs/CObservation3DRangeScan.h>
#include <mrpt/opengl/CRenderizable.h>
#include <mrpt/typemeta/TEnumType.h>
#include <sstream> // __str__
#include <string>
@@ -24,6 +24,17 @@

void bind_mrpt_typemeta_TEnumType_2(std::function< pybind11::module &(std::string const &namespace_) > &M)
{
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_opengl_TCullFace_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>(); } ) );
cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string> const &o){ return new mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>(o); } ) );
cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>::m_k2v);
cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>::m_v2k);
cl.def("direct", (bool (mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>::*)(const enum mrpt::opengl::TCullFace &, std::string &) const) &mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::direct, "C++: mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::direct(const enum mrpt::opengl::TCullFace &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v"));
cl.def("inverse", (bool (mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>::*)(const std::string &, enum mrpt::opengl::TCullFace &) const) &mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::inverse, "C++: mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::inverse(const std::string &, enum mrpt::opengl::TCullFace &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k"));
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>::*)(const enum mrpt::opengl::TCullFace &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::insert(const enum mrpt::opengl::TCullFace &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::opengl::TCullFace, std::string > & (mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::opengl::TCullFace, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::opengl::TCullFace, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::opengl::TCullFace, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::opengl::TCullFace, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::hwdrivers::TCameraType,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::hwdrivers::TCameraType,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_hwdrivers_TCameraType_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::hwdrivers::TCameraType,std::string>(); } ) );
@@ -68,15 +79,4 @@ void bind_mrpt_typemeta_TEnumType_2(std::function< pybind11::module &(std::strin
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGPSInterface::PARSERS,std::string>::*)(const enum mrpt::hwdrivers::CGPSInterface::PARSERS &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGPSInterface::PARSERS, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGPSInterface::PARSERS, std::string>::insert(const enum mrpt::hwdrivers::CGPSInterface::PARSERS &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CGPSInterface::PARSERS, std::string > & (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGPSInterface::PARSERS,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CGPSInterface::PARSERS, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGPSInterface::PARSERS, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CGPSInterface::PARSERS, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CGPSInterface::PARSERS, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CGPSInterface::PARSERS, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_hwdrivers_CVelodyneScanner_model_t_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>(); } ) );
cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string> const &o){ return new mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>(o); } ) );
cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>::m_k2v);
cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>::m_v2k);
cl.def("direct", (bool (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>::*)(const enum mrpt::hwdrivers::CVelodyneScanner::model_t &, std::string &) const) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::direct, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::direct(const enum mrpt::hwdrivers::CVelodyneScanner::model_t &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v"));
cl.def("inverse", (bool (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>::*)(const std::string &, enum mrpt::hwdrivers::CVelodyneScanner::model_t &) const) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::inverse, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::inverse(const std::string &, enum mrpt::hwdrivers::CVelodyneScanner::model_t &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k"));
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>::*)(const enum mrpt::hwdrivers::CVelodyneScanner::model_t &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::insert(const enum mrpt::hwdrivers::CVelodyneScanner::model_t &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CVelodyneScanner::model_t, std::string > & (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CVelodyneScanner::model_t, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CVelodyneScanner::model_t, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CVelodyneScanner::model_t, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
}
23 changes: 11 additions & 12 deletions python/src/mrpt/typemeta/TEnumType_3.cpp
Original file line number Diff line number Diff line change
@@ -3,7 +3,6 @@
#include <mrpt/hwdrivers/CVelodyneScanner.h>
#include <mrpt/maps/CColouredPointsMap.h>
#include <mrpt/maps/CHeightGridMap2D.h>
#include <mrpt/maps/COccupancyGridMap2D.h>
#include <mrpt/maps/CRandomFieldGridMap2D.h>
#include <mrpt/typemeta/TEnumType.h>
#include <sstream> // __str__
@@ -24,6 +23,17 @@

void bind_mrpt_typemeta_TEnumType_3(std::function< pybind11::module &(std::string const &namespace_) > &M)
{
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_hwdrivers_CVelodyneScanner_model_t_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>(); } ) );
cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string> const &o){ return new mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>(o); } ) );
cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>::m_k2v);
cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>::m_v2k);
cl.def("direct", (bool (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>::*)(const enum mrpt::hwdrivers::CVelodyneScanner::model_t &, std::string &) const) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::direct, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::direct(const enum mrpt::hwdrivers::CVelodyneScanner::model_t &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v"));
cl.def("inverse", (bool (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>::*)(const std::string &, enum mrpt::hwdrivers::CVelodyneScanner::model_t &) const) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::inverse, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::inverse(const std::string &, enum mrpt::hwdrivers::CVelodyneScanner::model_t &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k"));
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>::*)(const enum mrpt::hwdrivers::CVelodyneScanner::model_t &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::insert(const enum mrpt::hwdrivers::CVelodyneScanner::model_t &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CVelodyneScanner::model_t, std::string > & (mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CVelodyneScanner::model_t, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::model_t, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CVelodyneScanner::model_t, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::hwdrivers::CVelodyneScanner::model_t, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::return_type_t,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::return_type_t,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_hwdrivers_CVelodyneScanner_return_type_t_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::hwdrivers::CVelodyneScanner::return_type_t,std::string>(); } ) );
@@ -68,15 +78,4 @@ void bind_mrpt_typemeta_TEnumType_3(std::function< pybind11::module &(std::strin
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::maps::CHeightGridMap2D::TMapRepresentation,std::string>::*)(const enum mrpt::maps::CHeightGridMap2D::TMapRepresentation &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::maps::CHeightGridMap2D::TMapRepresentation, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::maps::CHeightGridMap2D::TMapRepresentation, std::string>::insert(const enum mrpt::maps::CHeightGridMap2D::TMapRepresentation &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::maps::CHeightGridMap2D::TMapRepresentation, std::string > & (mrpt::typemeta::internal::bimap<mrpt::maps::CHeightGridMap2D::TMapRepresentation,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::maps::CHeightGridMap2D::TMapRepresentation, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::maps::CHeightGridMap2D::TMapRepresentation, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::maps::CHeightGridMap2D::TMapRepresentation, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::maps::CHeightGridMap2D::TMapRepresentation, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::maps::CHeightGridMap2D::TMapRepresentation, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_maps_COccupancyGridMap2D_TLikelihoodMethod_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod,std::string>(); } ) );
cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod,std::string> const &o){ return new mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod,std::string>(o); } ) );
cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod,std::string>::m_k2v);
cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod,std::string>::m_v2k);
cl.def("direct", (bool (mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod,std::string>::*)(const enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod &, std::string &) const) &mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod, std::string>::direct, "C++: mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod, std::string>::direct(const enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v"));
cl.def("inverse", (bool (mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod,std::string>::*)(const std::string &, enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod &) const) &mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod, std::string>::inverse, "C++: mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod, std::string>::inverse(const std::string &, enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k"));
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod,std::string>::*)(const enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod, std::string>::insert(const enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod, std::string > & (mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
}
55 changes: 22 additions & 33 deletions python/src/mrpt/typemeta/TEnumType_4.cpp

Large diffs are not rendered by default.

46 changes: 35 additions & 11 deletions python/src/mrpt/typemeta/TEnumType_5.cpp
Original file line number Diff line number Diff line change
@@ -1,9 +1,11 @@
#include <iterator>
#include <memory>
#include <mrpt/bayes/CKalmanFilterCapable.h>
#include <mrpt/slam/CGridMapAligner.h>
#include <mrpt/slam/CIncrementalMapPartitioner.h>
#include <mrpt/slam/data_association.h>
#include <mrpt/typemeta/TEnumType.h>
#include <mrpt/vision/types.h>
#include <sstream> // __str__
#include <string>

@@ -22,6 +24,39 @@

void bind_mrpt_typemeta_TEnumType_5(std::function< pybind11::module &(std::string const &namespace_) > &M)
{
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_vision_TKeyPointMethod_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod,std::string>(); } ) );
cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod,std::string> const &o){ return new mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod,std::string>(o); } ) );
cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod,std::string>::m_k2v);
cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod,std::string>::m_v2k);
cl.def("direct", (bool (mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod,std::string>::*)(const enum mrpt::vision::TKeyPointMethod &, std::string &) const) &mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod, std::string>::direct, "C++: mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod, std::string>::direct(const enum mrpt::vision::TKeyPointMethod &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v"));
cl.def("inverse", (bool (mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod,std::string>::*)(const std::string &, enum mrpt::vision::TKeyPointMethod &) const) &mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod, std::string>::inverse, "C++: mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod, std::string>::inverse(const std::string &, enum mrpt::vision::TKeyPointMethod &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k"));
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod,std::string>::*)(const enum mrpt::vision::TKeyPointMethod &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod, std::string>::insert(const enum mrpt::vision::TKeyPointMethod &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::vision::TKeyPointMethod, std::string > & (mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::vision::TKeyPointMethod, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::vision::TKeyPointMethod, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::vision::TKeyPointMethod, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::vision::TKeyPointMethod, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_vision_TDescriptorType_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType,std::string>(); } ) );
cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType,std::string> const &o){ return new mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType,std::string>(o); } ) );
cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType,std::string>::m_k2v);
cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType,std::string>::m_v2k);
cl.def("direct", (bool (mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType,std::string>::*)(const enum mrpt::vision::TDescriptorType &, std::string &) const) &mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType, std::string>::direct, "C++: mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType, std::string>::direct(const enum mrpt::vision::TDescriptorType &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v"));
cl.def("inverse", (bool (mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType,std::string>::*)(const std::string &, enum mrpt::vision::TDescriptorType &) const) &mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType, std::string>::inverse, "C++: mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType, std::string>::inverse(const std::string &, enum mrpt::vision::TDescriptorType &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k"));
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType,std::string>::*)(const enum mrpt::vision::TDescriptorType &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType, std::string>::insert(const enum mrpt::vision::TDescriptorType &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::vision::TDescriptorType, std::string > & (mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::vision::TDescriptorType, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::vision::TDescriptorType, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::vision::TDescriptorType, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::vision::TDescriptorType, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_slam_CGridMapAligner_TAlignerMethod_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod,std::string>(); } ) );
cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod,std::string> const &o){ return new mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod,std::string>(o); } ) );
cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod,std::string>::m_k2v);
cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod,std::string>::m_v2k);
cl.def("direct", (bool (mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod,std::string>::*)(const enum mrpt::slam::CGridMapAligner::TAlignerMethod &, std::string &) const) &mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod, std::string>::direct, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod, std::string>::direct(const enum mrpt::slam::CGridMapAligner::TAlignerMethod &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v"));
cl.def("inverse", (bool (mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod,std::string>::*)(const std::string &, enum mrpt::slam::CGridMapAligner::TAlignerMethod &) const) &mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod, std::string>::inverse, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod, std::string>::inverse(const std::string &, enum mrpt::slam::CGridMapAligner::TAlignerMethod &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k"));
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod,std::string>::*)(const enum mrpt::slam::CGridMapAligner::TAlignerMethod &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod, std::string>::insert(const enum mrpt::slam::CGridMapAligner::TAlignerMethod &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::slam::CGridMapAligner::TAlignerMethod, std::string > & (mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::slam::CGridMapAligner::TAlignerMethod, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::CGridMapAligner::TAlignerMethod, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::slam::CGridMapAligner::TAlignerMethod, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::slam::CGridMapAligner::TAlignerMethod, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::slam::similarity_method_t,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::slam::similarity_method_t,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_slam_similarity_method_t_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::slam::similarity_method_t,std::string>(); } ) );
@@ -55,15 +90,4 @@ void bind_mrpt_typemeta_TEnumType_5(std::function< pybind11::module &(std::strin
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMethod,std::string>::*)(const enum mrpt::slam::TDataAssociationMethod &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMethod, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMethod, std::string>::insert(const enum mrpt::slam::TDataAssociationMethod &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::slam::TDataAssociationMethod, std::string > & (mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMethod,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::slam::TDataAssociationMethod, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMethod, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMethod, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::slam::TDataAssociationMethod, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::slam::TDataAssociationMethod, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_slam_TDataAssociationMetric_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>(); } ) );
cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string> const &o){ return new mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>(o); } ) );
cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>::m_k2v);
cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>::m_v2k);
cl.def("direct", (bool (mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>::*)(const enum mrpt::slam::TDataAssociationMetric &, std::string &) const) &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::direct, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::direct(const enum mrpt::slam::TDataAssociationMetric &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v"));
cl.def("inverse", (bool (mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>::*)(const std::string &, enum mrpt::slam::TDataAssociationMetric &) const) &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::inverse, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::inverse(const std::string &, enum mrpt::slam::TDataAssociationMetric &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k"));
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>::*)(const enum mrpt::slam::TDataAssociationMetric &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::insert(const enum mrpt::slam::TDataAssociationMetric &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::slam::TDataAssociationMetric, std::string > & (mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::slam::TDataAssociationMetric, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::slam::TDataAssociationMetric, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::slam::TDataAssociationMetric, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
}
26 changes: 11 additions & 15 deletions python/src/mrpt/typemeta/TEnumType_6.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#include <iterator>
#include <memory>
#include <mrpt/bayes/CKalmanFilterCapable.h>
#include <mrpt/system/COutputLogger.h>
#include <mrpt/slam/data_association.h>
#include <mrpt/typemeta/TEnumType.h>
#include <sstream> // __str__
#include <string>
@@ -21,18 +20,15 @@

void bind_mrpt_typemeta_TEnumType_6(std::function< pybind11::module &(std::string const &namespace_) > &M)
{
{ // mrpt::typemeta::TEnumType file:mrpt/typemeta/TEnumType.h line:94
pybind11::class_<mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>, std::shared_ptr<mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>>> cl(M("mrpt::typemeta"), "TEnumType_mrpt_bayes_TKFMethod_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>(); } ) );
cl.def_static("name2value", (enum mrpt::bayes::TKFMethod (*)(const std::string &)) &mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>::name2value, "C++: mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>::name2value(const std::string &) --> enum mrpt::bayes::TKFMethod", pybind11::arg("name"));
cl.def_static("value2name", (std::string (*)(const enum mrpt::bayes::TKFMethod)) &mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>::value2name, "C++: mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>::value2name(const enum mrpt::bayes::TKFMethod) --> std::string", pybind11::arg("val"));
cl.def_static("getBimap", (struct mrpt::typemeta::internal::bimap<enum mrpt::bayes::TKFMethod, std::string > & (*)()) &mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>::getBimap, "C++: mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>::getBimap() --> struct mrpt::typemeta::internal::bimap<enum mrpt::bayes::TKFMethod, std::string > &", pybind11::return_value_policy::automatic);
}
{ // mrpt::typemeta::TEnumType file:mrpt/typemeta/TEnumType.h line:94
pybind11::class_<mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>, std::shared_ptr<mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>>> cl(M("mrpt::typemeta"), "TEnumType_mrpt_system_VerbosityLevel_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>(); } ) );
cl.def_static("name2value", (enum mrpt::system::VerbosityLevel (*)(const std::string &)) &mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>::name2value, "C++: mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>::name2value(const std::string &) --> enum mrpt::system::VerbosityLevel", pybind11::arg("name"));
cl.def_static("value2name", (std::string (*)(const enum mrpt::system::VerbosityLevel)) &mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>::value2name, "C++: mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>::value2name(const enum mrpt::system::VerbosityLevel) --> std::string", pybind11::arg("val"));
cl.def_static("getBimap", (struct mrpt::typemeta::internal::bimap<enum mrpt::system::VerbosityLevel, std::string > & (*)()) &mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>::getBimap, "C++: mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>::getBimap() --> struct mrpt::typemeta::internal::bimap<enum mrpt::system::VerbosityLevel, std::string > &", pybind11::return_value_policy::automatic);
{ // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22
pybind11::class_<mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>, std::shared_ptr<mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_slam_TDataAssociationMetric_std_string_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>(); } ) );
cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string> const &o){ return new mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>(o); } ) );
cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>::m_k2v);
cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>::m_v2k);
cl.def("direct", (bool (mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>::*)(const enum mrpt::slam::TDataAssociationMetric &, std::string &) const) &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::direct, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::direct(const enum mrpt::slam::TDataAssociationMetric &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v"));
cl.def("inverse", (bool (mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>::*)(const std::string &, enum mrpt::slam::TDataAssociationMetric &) const) &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::inverse, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::inverse(const std::string &, enum mrpt::slam::TDataAssociationMetric &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k"));
cl.def("insert", (void (mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>::*)(const enum mrpt::slam::TDataAssociationMetric &, const std::string &)) &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::insert, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::insert(const enum mrpt::slam::TDataAssociationMetric &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v"));
cl.def("assign", (struct mrpt::typemeta::internal::bimap<enum mrpt::slam::TDataAssociationMetric, std::string > & (mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric,std::string>::*)(const struct mrpt::typemeta::internal::bimap<enum mrpt::slam::TDataAssociationMetric, std::string > &)) &mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::operator=, "C++: mrpt::typemeta::internal::bimap<mrpt::slam::TDataAssociationMetric, std::string>::operator=(const struct mrpt::typemeta::internal::bimap<enum mrpt::slam::TDataAssociationMetric, std::string > &) --> struct mrpt::typemeta::internal::bimap<enum mrpt::slam::TDataAssociationMetric, std::string > &", pybind11::return_value_policy::automatic, pybind11::arg(""));
}
}
38 changes: 38 additions & 0 deletions python/src/mrpt/typemeta/TEnumType_7.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
#include <iterator>
#include <memory>
#include <mrpt/bayes/CKalmanFilterCapable.h>
#include <mrpt/system/COutputLogger.h>
#include <mrpt/typemeta/TEnumType.h>
#include <sstream> // __str__
#include <string>

#include <functional>
#include <pybind11/pybind11.h>
#include <string>
#include <pybind11/stl.h>


#ifndef BINDER_PYBIND11_TYPE_CASTER
#define BINDER_PYBIND11_TYPE_CASTER
PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr<T>)
PYBIND11_DECLARE_HOLDER_TYPE(T, T*)
PYBIND11_MAKE_OPAQUE(std::shared_ptr<void>)
#endif

void bind_mrpt_typemeta_TEnumType_7(std::function< pybind11::module &(std::string const &namespace_) > &M)
{
{ // mrpt::typemeta::TEnumType file:mrpt/typemeta/TEnumType.h line:94
pybind11::class_<mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>, std::shared_ptr<mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>>> cl(M("mrpt::typemeta"), "TEnumType_mrpt_bayes_TKFMethod_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>(); } ) );
cl.def_static("name2value", (enum mrpt::bayes::TKFMethod (*)(const std::string &)) &mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>::name2value, "C++: mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>::name2value(const std::string &) --> enum mrpt::bayes::TKFMethod", pybind11::arg("name"));
cl.def_static("value2name", (std::string (*)(const enum mrpt::bayes::TKFMethod)) &mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>::value2name, "C++: mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>::value2name(const enum mrpt::bayes::TKFMethod) --> std::string", pybind11::arg("val"));
cl.def_static("getBimap", (struct mrpt::typemeta::internal::bimap<enum mrpt::bayes::TKFMethod, std::string > & (*)()) &mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>::getBimap, "C++: mrpt::typemeta::TEnumType<mrpt::bayes::TKFMethod>::getBimap() --> struct mrpt::typemeta::internal::bimap<enum mrpt::bayes::TKFMethod, std::string > &", pybind11::return_value_policy::automatic);
}
{ // mrpt::typemeta::TEnumType file:mrpt/typemeta/TEnumType.h line:94
pybind11::class_<mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>, std::shared_ptr<mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>>> cl(M("mrpt::typemeta"), "TEnumType_mrpt_system_VerbosityLevel_t", "");
cl.def( pybind11::init( [](){ return new mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>(); } ) );
cl.def_static("name2value", (enum mrpt::system::VerbosityLevel (*)(const std::string &)) &mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>::name2value, "C++: mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>::name2value(const std::string &) --> enum mrpt::system::VerbosityLevel", pybind11::arg("name"));
cl.def_static("value2name", (std::string (*)(const enum mrpt::system::VerbosityLevel)) &mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>::value2name, "C++: mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>::value2name(const enum mrpt::system::VerbosityLevel) --> std::string", pybind11::arg("val"));
cl.def_static("getBimap", (struct mrpt::typemeta::internal::bimap<enum mrpt::system::VerbosityLevel, std::string > & (*)()) &mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>::getBimap, "C++: mrpt::typemeta::TEnumType<mrpt::system::VerbosityLevel>::getBimap() --> struct mrpt::typemeta::internal::bimap<enum mrpt::system::VerbosityLevel, std::string > &", pybind11::return_value_policy::automatic);
}
}
Loading

0 comments on commit 6763374

Please sign in to comment.