diff --git a/README.md b/README.md index 222c9f9efa..7449f9ae69 100644 --- a/README.md +++ b/README.md @@ -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 | |---|---| diff --git a/appveyor.yml b/appveyor.yml index 8e05d52210..805adbb033 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -1,5 +1,5 @@ # version format -version: 2.11.11-{branch}-build{build} +version: 2.11.12-{branch}-build{build} os: Visual Studio 2019 diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 7110e56de6..56c60ac5ab 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -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: diff --git a/libs/hwdrivers/include/mrpt/hwdrivers/CGPSInterface.h b/libs/hwdrivers/include/mrpt/hwdrivers/CGPSInterface.h index 6b815f27d8..bce93b42c0 100644 --- a/libs/hwdrivers/include/mrpt/hwdrivers/CGPSInterface.h +++ b/libs/hwdrivers/include/mrpt/hwdrivers/CGPSInterface.h @@ -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 diff --git a/libs/hwdrivers/src/CGPSInterface.cpp b/libs/hwdrivers/src/CGPSInterface.cpp index bde2d82375..aeccfb9dcf 100644 --- a/libs/hwdrivers/src/CGPSInterface.cpp +++ b/libs/hwdrivers/src/CGPSInterface.cpp @@ -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(); - 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") || diff --git a/libs/hwdrivers/src/CGPSInterface_parser_NMEA.cpp b/libs/hwdrivers/src/CGPSInterface_parser_NMEA.cpp index 8696f2b271..e0b251a8ca 100644 --- a/libs/hwdrivers/src/CGPSInterface_parser_NMEA.cpp +++ b/libs/hwdrivers/src/CGPSInterface_parser_NMEA.cpp @@ -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 diff --git a/libs/hwdrivers/src/CGPSInterface_parser_NOVATEL_OEM6.cpp b/libs/hwdrivers/src/CGPSInterface_parser_NOVATEL_OEM6.cpp index fdf67a164b..6a69d86922 100644 --- a/libs/hwdrivers/src/CGPSInterface_parser_NOVATEL_OEM6.cpp +++ b/libs/hwdrivers/src/CGPSInterface_parser_NOVATEL_OEM6.cpp @@ -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 diff --git a/libs/hwdrivers/src/CGPSInterface_unittest.cpp b/libs/hwdrivers/src/CGPSInterface_unittest.cpp index 80eb7c481f..a3906efeb6 100644 --- a/libs/hwdrivers/src/CGPSInterface_unittest.cpp +++ b/libs/hwdrivers/src/CGPSInterface_unittest.cpp @@ -370,19 +370,19 @@ TEST(CGPSInterface, parse_NMEA_stream) EXPECT_TRUE(obsGPS2); EXPECT_TRUE(obsGPS3); - const auto* msg1 = obsGPS1->getMsgByClassPtr(); - 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(); - EXPECT_TRUE(msg2 != nullptr); - - const auto* msg3 = obsGPS3->getMsgByClassPtr(); - 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(); + 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(); + 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(); + EXPECT_TRUE(msgGSA2 != nullptr); } diff --git a/libs/obs/include/mrpt/obs/CObservationGPS.h b/libs/obs/include/mrpt/obs/CObservationGPS.h index 3102013e03..96eb1a908b 100644 --- a/libs/obs/include/mrpt/obs/CObservationGPS.h +++ b/libs/obs/include/mrpt/obs/CObservationGPS.h @@ -8,6 +8,7 @@ +------------------------------------------------------------------------+ */ #pragma once +#include #include #include #include @@ -15,6 +16,7 @@ #include #include +#include #include 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 [API changed in MRPT 1.4.0] 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().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 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(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(MSG_CLASS::msg_type)); return it == messages.end() - ? dynamic_cast(nullptr) - : dynamic_cast(it->second.get()); + ? static_cast(nullptr) + : dynamic_cast(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 { diff --git a/libs/obs/include/mrpt/obs/gnss_messages_common.h b/libs/obs/include/mrpt/obs/gnss_messages_common.h index 56599c22b9..a44ab449cf 100644 --- a/libs/obs/include/mrpt/obs/gnss_messages_common.h +++ b/libs/obs/include/mrpt/obs/gnss_messages_common.h @@ -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; #define GNSS_MESSAGE_BINARY_BLOCK(DATA_PTR, DATA_LEN) \ protected: \ diff --git a/libs/obs/src/CObservationComment.cpp b/libs/obs/src/CObservationComment.cpp index 7c0bf898f7..fd06d471b7 100644 --- a/libs/obs/src/CObservationComment.cpp +++ b/libs/obs/src/CObservationComment.cpp @@ -20,10 +20,11 @@ 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( @@ -31,7 +32,11 @@ void CObservationComment::serializeFrom( { 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); }; } diff --git a/libs/obs/src/CObservationGPS.cpp b/libs/obs/src/CObservationGPS.cpp index dd23548ea8..acc71539fb 100644 --- a/libs/obs/src/CObservationGPS.cpp +++ b/libs/obs/src/CObservationGPS.cpp @@ -12,6 +12,7 @@ #include // for << of matrices #include #include +#include #include @@ -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 diff --git a/libs/obs/src/CObservationRobotPose.cpp b/libs/obs/src/CObservationRobotPose.cpp index aa28be134d..0422501bdb 100644 --- a/libs/obs/src/CObservationRobotPose.cpp +++ b/libs/obs/src/CObservationRobotPose.cpp @@ -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: diff --git a/libs/obs/src/gnss_messages_common.cpp b/libs/obs/src/gnss_messages_common.cpp index c41af2758c..60e0e0f3d7 100644 --- a/libs/obs/src/gnss_messages_common.cpp +++ b/libs/obs/src/gnss_messages_common.cpp @@ -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(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 diff --git a/libs/ros1bridge/include/mrpt/ros1bridge/gps.h b/libs/ros1bridge/include/mrpt/ros1bridge/gps.h index fa469a11cd..91b4a8570b 100644 --- a/libs/ros1bridge/include/mrpt/ros1bridge/gps.h +++ b/libs/ros1bridge/include/mrpt/ros1bridge/gps.h @@ -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, diff --git a/libs/ros1bridge/src/gps.cpp b/libs/ros1bridge/src/gps.cpp index a52eaa1919..9aebae458e 100644 --- a/libs/ros1bridge/src/gps.cpp +++ b/libs/ros1bridge/src/gps.cpp @@ -14,6 +14,7 @@ ---------------------------------------------------------------*/ #include +#include bool mrpt::ros1bridge::fromROS( const sensor_msgs::NavSatFix& msg, mrpt::obs::CObservationGPS& obj) @@ -32,6 +33,18 @@ 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; } @@ -39,6 +52,8 @@ 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 diff --git a/libs/ros1bridge/src/image.cpp b/libs/ros1bridge/src/image.cpp index a040cd2422..0a4123c525 100644 --- a/libs/ros1bridge/src/image.cpp +++ b/libs/ros1bridge/src/image.cpp @@ -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(); diff --git a/libs/ros2bridge/include/mrpt/ros2bridge/gps.h b/libs/ros2bridge/include/mrpt/ros2bridge/gps.h index a16d604207..498cf2579c 100644 --- a/libs/ros2bridge/include/mrpt/ros2bridge/gps.h +++ b/libs/ros2bridge/include/mrpt/ros2bridge/gps.h @@ -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, diff --git a/libs/ros2bridge/src/gps.cpp b/libs/ros2bridge/src/gps.cpp index 991aa07a8f..63dcc74694 100644 --- a/libs/ros2bridge/src/gps.cpp +++ b/libs/ros2bridge/src/gps.cpp @@ -14,6 +14,7 @@ ---------------------------------------------------------------*/ #include +#include bool mrpt::ros2bridge::fromROS( const sensor_msgs::msg::NavSatFix& msg, mrpt::obs::CObservationGPS& obj) @@ -32,6 +33,18 @@ 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; } @@ -39,6 +52,8 @@ 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 diff --git a/libs/ros2bridge/src/image.cpp b/libs/ros2bridge/src/image.cpp index 9cdf963607..53151ac13e 100644 --- a/libs/ros2bridge/src/image.cpp +++ b/libs/ros2bridge/src/image.cpp @@ -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(); diff --git a/libs/topography/src/path_from_rtk_gps.cpp b/libs/topography/src/path_from_rtk_gps.cpp index 62243ed95e..330915bd1e 100644 --- a/libs/topography/src/path_from_rtk_gps.cpp +++ b/libs/topography/src/path_from_rtk_gps.cpp @@ -61,8 +61,8 @@ void mrpt::topography::path_from_rtk_gps( TPathFromRTKInfo outInfoTemp; if (outInfo) *outInfo = outInfoTemp; - map> - gps_paths; // label -> (time -> 3D local coords) + // label -> (time -> 3D local coords) + map> gps_paths; bool abort = false; bool ref_valid = false; diff --git a/libs/topography/src/path_from_rtk_gps_unittest.cpp b/libs/topography/src/path_from_rtk_gps_unittest.cpp index 42e90a305e..b811b2f3d3 100644 --- a/libs/topography/src/path_from_rtk_gps_unittest.cpp +++ b/libs/topography/src/path_from_rtk_gps_unittest.cpp @@ -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; diff --git a/package.xml b/package.xml index bc9d027a2a..c09c7add8f 100644 --- a/package.xml +++ b/package.xml @@ -7,7 +7,7 @@ mrpt2 - 2.11.11 + 2.11.12 Mobile Robot Programming Toolkit (MRPT) version 2.x Jose-Luis Blanco-Claraco diff --git a/python/all_mrpt_obs.cpp b/python/all_mrpt_obs.cpp index 3d7b01f875..4ddd98d84c 100644 --- a/python/all_mrpt_obs.cpp +++ b/python/all_mrpt_obs.cpp @@ -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" diff --git a/python/all_mrpt_obs2.cpp b/python/all_mrpt_obs2.cpp index 4848cdaf9b..9f9be38f78 100644 --- a/python/all_mrpt_obs2.cpp +++ b/python/all_mrpt_obs2.cpp @@ -1,7 +1,6 @@ #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" @@ -9,3 +8,5 @@ #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" \ No newline at end of file diff --git a/python/all_mrpt_obs3.cpp b/python/all_mrpt_obs3.cpp index 63a1d2317b..f5fd0addf9 100644 --- a/python/all_mrpt_obs3.cpp +++ b/python/all_mrpt_obs3.cpp @@ -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" diff --git a/python/all_mrpt_typemeta.cpp b/python/all_mrpt_typemeta.cpp index 1b5728d468..e1542404ed 100644 --- a/python/all_mrpt_typemeta.cpp +++ b/python/all_mrpt_typemeta.cpp @@ -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" diff --git a/python/all_unknown.cpp b/python/all_unknown.cpp index 05194d56eb..1a7e68d7c5 100644 --- a/python/all_unknown.cpp +++ b/python/all_unknown.cpp @@ -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" diff --git a/python/src/mrpt/math/MatrixBase.cpp b/python/src/mrpt/math/MatrixBase.cpp deleted file mode 100644 index 118a85c885..0000000000 --- a/python/src/mrpt/math/MatrixBase.cpp +++ /dev/null @@ -1,88 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include // __str__ -#include -#include - -#include -#include -#include -#include - - -#ifndef BINDER_PYBIND11_TYPE_CASTER - #define BINDER_PYBIND11_TYPE_CASTER - PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) - PYBIND11_DECLARE_HOLDER_TYPE(T, T*) - PYBIND11_MAKE_OPAQUE(std::shared_ptr) -#endif - -void bind_mrpt_math_MatrixBase(std::function< pybind11::module &(std::string const &namespace_) > &M) -{ - { // mrpt::math::MatrixBase file:mrpt/math/MatrixBase.h line:23 - pybind11::class_,mrpt::math::CMatrixDynamic >>, std::shared_ptr,mrpt::math::CMatrixDynamic >>>, mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>> cl(M("mrpt::math"), "MatrixBase_mrpt_math_TPoint3D_float_mrpt_math_CMatrixDynamic_mrpt_math_TPoint3D_float_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>(); } ) ); - cl.def( pybind11::init( [](mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >> const &o){ return new mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>(o); } ) ); - cl.def("mbDerived", (class mrpt::math::CMatrixDynamic > & (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)()) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::mbDerived, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::mbDerived() --> class mrpt::math::CMatrixDynamic > &", pybind11::return_value_policy::automatic); - cl.def("setDiagonal", (void (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(const unsigned long, const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setDiagonal, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setDiagonal(const unsigned long, const struct mrpt::math::TPoint3D_) --> void", pybind11::arg("N"), pybind11::arg("value")); - cl.def("setDiagonal", (void (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setDiagonal, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setDiagonal(const struct mrpt::math::TPoint3D_) --> void", pybind11::arg("value")); - cl.def("setIdentity", (void (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)()) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setIdentity, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setIdentity() --> void"); - cl.def("setIdentity", (void (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(const unsigned long)) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setIdentity, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setIdentity(const unsigned long) --> void", pybind11::arg("N")); - cl.def_static("Identity", (class mrpt::math::CMatrixDynamic > (*)()) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::Identity, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::Identity() --> class mrpt::math::CMatrixDynamic >"); - cl.def_static("Identity", (class mrpt::math::CMatrixDynamic > (*)(const unsigned long)) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::Identity, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::Identity(const unsigned long) --> class mrpt::math::CMatrixDynamic >", pybind11::arg("N")); - cl.def("matProductOf_AB", (void (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(const class mrpt::math::CMatrixDynamic > &, const class mrpt::math::CMatrixDynamic > &)) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::matProductOf_AB, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::matProductOf_AB(const class mrpt::math::CMatrixDynamic > &, const class mrpt::math::CMatrixDynamic > &) --> void", pybind11::arg("A"), pybind11::arg("B")); - cl.def("det", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::det, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::det() const --> struct mrpt::math::TPoint3D_"); - cl.def("inverse", (class mrpt::math::CMatrixDynamic > (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::inverse, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::inverse() const --> class mrpt::math::CMatrixDynamic >"); - cl.def("inverse_LLt", (class mrpt::math::CMatrixDynamic > (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::inverse_LLt, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::inverse_LLt() const --> class mrpt::math::CMatrixDynamic >"); - cl.def("rank", [](mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >> const &o) -> int { return o.rank(); }, ""); - cl.def("rank", (int (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(struct mrpt::math::TPoint3D_) const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::rank, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::rank(struct mrpt::math::TPoint3D_) const --> int", pybind11::arg("threshold")); - cl.def("chol", (bool (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(class mrpt::math::CMatrixDynamic > &) const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::chol, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::chol(class mrpt::math::CMatrixDynamic > &) const --> bool", pybind11::arg("U")); - cl.def("maximumDiagonal", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::maximumDiagonal, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::maximumDiagonal() const --> struct mrpt::math::TPoint3D_"); - cl.def("minimumDiagonal", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::minimumDiagonal, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::minimumDiagonal() const --> struct mrpt::math::TPoint3D_"); - cl.def("trace", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::trace, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::trace() const --> struct mrpt::math::TPoint3D_"); - cl.def("assign", (class mrpt::math::MatrixBase, class mrpt::math::CMatrixDynamic > > & (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(const class mrpt::math::MatrixBase, class mrpt::math::CMatrixDynamic > > &)) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::operator=, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::operator=(const class mrpt::math::MatrixBase, class mrpt::math::CMatrixDynamic > > &) --> class mrpt::math::MatrixBase, class mrpt::math::CMatrixDynamic > > &", pybind11::return_value_policy::automatic, pybind11::arg("")); - cl.def("fill", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const struct mrpt::math::TPoint3D_ &)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::fill, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::fill(const struct mrpt::math::TPoint3D_ &) --> void", pybind11::arg("val")); - cl.def("setConstant", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setConstant, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setConstant(const struct mrpt::math::TPoint3D_) --> void", pybind11::arg("value")); - cl.def("setConstant", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(size_t, size_t, const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setConstant, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setConstant(size_t, size_t, const struct mrpt::math::TPoint3D_) --> void", pybind11::arg("nrows"), pybind11::arg("ncols"), pybind11::arg("value")); - cl.def("setConstant", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(size_t, const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setConstant, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setConstant(size_t, const struct mrpt::math::TPoint3D_) --> void", pybind11::arg("nrows"), pybind11::arg("value")); - cl.def_static("Constant", (class mrpt::math::CMatrixDynamic > (*)(const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Constant, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Constant(const struct mrpt::math::TPoint3D_) --> class mrpt::math::CMatrixDynamic >", pybind11::arg("value")); - cl.def_static("Constant", (class mrpt::math::CMatrixDynamic > (*)(size_t, size_t, const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Constant, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Constant(size_t, size_t, const struct mrpt::math::TPoint3D_) --> class mrpt::math::CMatrixDynamic >", pybind11::arg("nrows"), pybind11::arg("ncols"), pybind11::arg("value")); - cl.def("assign", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const unsigned long, const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::assign, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::assign(const unsigned long, const struct mrpt::math::TPoint3D_) --> void", pybind11::arg("N"), pybind11::arg("value")); - cl.def("setZero", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)()) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setZero, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setZero() --> void"); - cl.def("setZero", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(size_t, size_t)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setZero, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setZero(size_t, size_t) --> void", pybind11::arg("nrows"), pybind11::arg("ncols")); - cl.def("setZero", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(size_t)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setZero, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setZero(size_t) --> void", pybind11::arg("nrows")); - cl.def_static("Zero", (class mrpt::math::CMatrixDynamic > (*)()) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Zero, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Zero() --> class mrpt::math::CMatrixDynamic >"); - cl.def_static("Zero", (class mrpt::math::CMatrixDynamic > (*)(size_t, size_t)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Zero, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Zero(size_t, size_t) --> class mrpt::math::CMatrixDynamic >", pybind11::arg("nrows"), pybind11::arg("ncols")); - cl.def("coeffRef", (struct mrpt::math::TPoint3D_ & (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(int, int)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::coeffRef, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::coeffRef(int, int) --> struct mrpt::math::TPoint3D_ &", pybind11::return_value_policy::automatic, pybind11::arg("r"), pybind11::arg("c")); - cl.def("coeff", (const struct mrpt::math::TPoint3D_ & (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(int, int) const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::coeff, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::coeff(int, int) const --> const struct mrpt::math::TPoint3D_ &", pybind11::return_value_policy::automatic, pybind11::arg("r"), pybind11::arg("c")); - cl.def("isSquare", (bool (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::isSquare, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::isSquare() const --> bool"); - cl.def("empty", (bool (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::empty, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::empty() const --> bool"); - cl.def("norm_inf", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::norm_inf, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::norm_inf() const --> struct mrpt::math::TPoint3D_"); - cl.def("norm", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::norm, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::norm() const --> struct mrpt::math::TPoint3D_"); - cl.def("__iadd__", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator+=, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator+=(struct mrpt::math::TPoint3D_) --> void", pybind11::arg("s")); - cl.def("__isub__", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator-=, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator-=(struct mrpt::math::TPoint3D_) --> void", pybind11::arg("s")); - cl.def("__imul__", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator*=, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator*=(struct mrpt::math::TPoint3D_) --> void", pybind11::arg("s")); - cl.def("__add__", (class mrpt::math::CMatrixDynamic > (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const class mrpt::math::CMatrixDynamic > &) const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator+, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator+(const class mrpt::math::CMatrixDynamic > &) const --> class mrpt::math::CMatrixDynamic >", pybind11::arg("m2")); - cl.def("__iadd__", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const class mrpt::math::CMatrixDynamic > &)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator+=, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator+=(const class mrpt::math::CMatrixDynamic > &) --> void", pybind11::arg("m2")); - cl.def("__isub__", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const class mrpt::math::CMatrixDynamic > &)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator-=, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator-=(const class mrpt::math::CMatrixDynamic > &) --> void", pybind11::arg("m2")); - cl.def("sum", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::sum, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::sum() const --> struct mrpt::math::TPoint3D_"); - cl.def("sum_abs", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::sum_abs, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::sum_abs() const --> struct mrpt::math::TPoint3D_"); - cl.def("asString", (std::string (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::asString, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::asString() const --> std::string"); - cl.def("inMatlabFormat", [](mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >> const &o) -> std::string { return o.inMatlabFormat(); }, ""); - cl.def("inMatlabFormat", (std::string (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const unsigned long) const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::inMatlabFormat, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::inMatlabFormat(const unsigned long) const --> std::string", pybind11::arg("decimal_digits")); - cl.def("saveToTextFile", [](mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >> const &o, const std::string & a0) -> void { return o.saveToTextFile(a0); }, "", pybind11::arg("file")); - cl.def("saveToTextFile", [](mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >> const &o, const std::string & a0, enum mrpt::math::TMatrixTextFileFormat const & a1) -> void { return o.saveToTextFile(a0, a1); }, "", pybind11::arg("file"), pybind11::arg("fileFormat")); - cl.def("saveToTextFile", [](mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >> const &o, const std::string & a0, enum mrpt::math::TMatrixTextFileFormat const & a1, bool const & a2) -> void { return o.saveToTextFile(a0, a1, a2); }, "", pybind11::arg("file"), pybind11::arg("fileFormat"), pybind11::arg("appendMRPTHeader")); - cl.def("saveToTextFile", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const std::string &, enum mrpt::math::TMatrixTextFileFormat, bool, const std::string &) const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::saveToTextFile, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::saveToTextFile(const std::string &, enum mrpt::math::TMatrixTextFileFormat, bool, const std::string &) const --> void", pybind11::arg("file"), pybind11::arg("fileFormat"), pybind11::arg("appendMRPTHeader"), pybind11::arg("userHeader")); - cl.def("loadFromTextFile", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const std::string &)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::loadFromTextFile, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::loadFromTextFile(const std::string &) --> void", pybind11::arg("file")); - cl.def("assign", (class mrpt::math::MatrixVectorBase, class mrpt::math::CMatrixDynamic > > & (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const class mrpt::math::MatrixVectorBase, class mrpt::math::CMatrixDynamic > > &)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator=, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator=(const class mrpt::math::MatrixVectorBase, class mrpt::math::CMatrixDynamic > > &) --> class mrpt::math::MatrixVectorBase, class mrpt::math::CMatrixDynamic > > &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } -} diff --git a/python/src/mrpt/obs/CActionRobotMovement3D.cpp b/python/src/mrpt/obs/CActionRobotMovement3D.cpp index 1bc0438571..5e36b894dc 100644 --- a/python/src/mrpt/obs/CActionRobotMovement3D.cpp +++ b/python/src/mrpt/obs/CActionRobotMovement3D.cpp @@ -1,46 +1,19 @@ -#include -#include -#include #include -#include #include -#include #include -#include -#include -#include -#include -#include #include #include #include -#include -#include #include #include -#include #include -#include -#include -#include #include -#include -#include -#include -#include -#include -#include #include #include -#include #include #include -#include #include -#include #include -#include -#include #include #include #include @@ -48,16 +21,10 @@ #include #include #include -#include #include // __str__ #include #include -#include -#include -#include -#include #include -#include #include #include @@ -72,7 +39,7 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::CActionRobotMovement3D file:mrpt/obs/CActionRobotMovement3D.h line:27 +// mrpt::obs::CActionRobotMovement3D file:mrpt/obs/CActionRobotMovement3D.h line:28 struct PyCallBack_mrpt_obs_CActionRobotMovement3D : public mrpt::obs::CActionRobotMovement3D { using mrpt::obs::CActionRobotMovement3D::CActionRobotMovement3D; @@ -143,400 +110,9 @@ struct PyCallBack_mrpt_obs_CActionRobotMovement3D : public mrpt::obs::CActionRob } }; -// mrpt::obs::CObservation3DScene file:mrpt/obs/CObservation3DScene.h line:28 -struct PyCallBack_mrpt_obs_CObservation3DScene : public mrpt::obs::CObservation3DScene { - using mrpt::obs::CObservation3DScene::CObservation3DScene; - - const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation3DScene::GetRuntimeClass(); - } - class mrpt::rtti::CObject * clone() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation3DScene::clone(); - } - uint8_t serializeGetVersion() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation3DScene::serializeGetVersion(); - } - void serializeTo(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation3DScene::serializeTo(a0); - } - void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); - if (overload) { - auto o = overload.operator()(a0, a1); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation3DScene::serializeFrom(a0, a1); - } - void getSensorPose(class mrpt::poses::CPose3D & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation3DScene::getSensorPose(a0); - } - void setSensorPose(const class mrpt::poses::CPose3D & a0) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation3DScene::setSensorPose(a0); - } - void getVisualizationInto(class mrpt::opengl::CSetOfObjects & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getVisualizationInto"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation3DScene::getVisualizationInto(a0); - } - using _binder_ret_0 = mrpt::Clock::time_point; - _binder_ret_0 getOriginalReceivedTimeStamp() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { - static pybind11::detail::override_caster_t<_binder_ret_0> caster; - return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); - } - else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); - } - return CObservation::getOriginalReceivedTimeStamp(); - } - std::string asString() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation::asString(); - } - bool exportTxtSupported() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation::exportTxtSupported(); - } - std::string exportTxtHeader() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation::exportTxtHeader(); - } - std::string exportTxtDataRow() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation::exportTxtDataRow(); - } - void unload() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation::unload(); - } - void load_impl() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation::load_impl(); - } -}; - -// mrpt::obs::CObservation6DFeatures file:mrpt/obs/CObservation6DFeatures.h line:26 -struct PyCallBack_mrpt_obs_CObservation6DFeatures : public mrpt::obs::CObservation6DFeatures { - using mrpt::obs::CObservation6DFeatures::CObservation6DFeatures; - - const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation6DFeatures::GetRuntimeClass(); - } - class mrpt::rtti::CObject * clone() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation6DFeatures::clone(); - } - uint8_t serializeGetVersion() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation6DFeatures::serializeGetVersion(); - } - void serializeTo(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation6DFeatures::serializeTo(a0); - } - void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); - if (overload) { - auto o = overload.operator()(a0, a1); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation6DFeatures::serializeFrom(a0, a1); - } - void getSensorPose(class mrpt::poses::CPose3D & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation6DFeatures::getSensorPose(a0); - } - void setSensorPose(const class mrpt::poses::CPose3D & a0) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation6DFeatures::setSensorPose(a0); - } - using _binder_ret_0 = mrpt::Clock::time_point; - _binder_ret_0 getOriginalReceivedTimeStamp() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { - static pybind11::detail::override_caster_t<_binder_ret_0> caster; - return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); - } - else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); - } - return CObservation::getOriginalReceivedTimeStamp(); - } - std::string asString() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation::asString(); - } - bool exportTxtSupported() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation::exportTxtSupported(); - } - std::string exportTxtHeader() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation::exportTxtHeader(); - } - std::string exportTxtDataRow() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation::exportTxtDataRow(); - } - void unload() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation::unload(); - } - void load_impl() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CObservation::load_impl(); - } -}; - void bind_mrpt_obs_CActionRobotMovement3D(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::CActionRobotMovement3D file:mrpt/obs/CActionRobotMovement3D.h line:27 + { // mrpt::obs::CActionRobotMovement3D file:mrpt/obs/CActionRobotMovement3D.h line:28 pybind11::class_, PyCallBack_mrpt_obs_CActionRobotMovement3D, mrpt::obs::CAction> cl(M("mrpt::obs"), "CActionRobotMovement3D", "Represents a probabilistic motion increment in SE(3).\n\n Odometry increments might be determined from visual odometry for full 3D, or\n from wheel encoders for 2D movements only.\n\n The implemented model for creating a SE(3) Gaussian from an odometry\n increment is based on \n\n \n\n \n CAction, CActionRobotMovement3D,"); cl.def( pybind11::init( [](){ return new mrpt::obs::CActionRobotMovement3D(); }, [](){ return new PyCallBack_mrpt_obs_CActionRobotMovement3D(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CActionRobotMovement3D const &o){ return new PyCallBack_mrpt_obs_CActionRobotMovement3D(o); } ) ); @@ -567,7 +143,7 @@ void bind_mrpt_obs_CActionRobotMovement3D(std::function< pybind11::module &(std: cl.def("computeFromOdometry_model6DOF", (void (mrpt::obs::CActionRobotMovement3D::*)(const class mrpt::poses::CPose3D &, const struct mrpt::obs::CActionRobotMovement3D::TMotionModelOptions &)) &mrpt::obs::CActionRobotMovement3D::computeFromOdometry_model6DOF, "Computes the PDF of the pose increment from an odometry reading, using\n the motion model for 6 DOF.\n\n Based on: \n\n \n computeFromOdometry\n\nC++: mrpt::obs::CActionRobotMovement3D::computeFromOdometry_model6DOF(const class mrpt::poses::CPose3D &, const struct mrpt::obs::CActionRobotMovement3D::TMotionModelOptions &) --> void", pybind11::arg("odometryIncrement"), pybind11::arg("o")); cl.def("assign", (class mrpt::obs::CActionRobotMovement3D & (mrpt::obs::CActionRobotMovement3D::*)(const class mrpt::obs::CActionRobotMovement3D &)) &mrpt::obs::CActionRobotMovement3D::operator=, "C++: mrpt::obs::CActionRobotMovement3D::operator=(const class mrpt::obs::CActionRobotMovement3D &) --> class mrpt::obs::CActionRobotMovement3D &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::CActionRobotMovement3D::TMotionModelOptions file:mrpt/obs/CActionRobotMovement3D.h line:64 + { // mrpt::obs::CActionRobotMovement3D::TMotionModelOptions file:mrpt/obs/CActionRobotMovement3D.h line:65 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMotionModelOptions", "The parameter to be passed to \"computeFromOdometry\".\n See: "); cl.def( pybind11::init( [](){ return new mrpt::obs::CActionRobotMovement3D::TMotionModelOptions(); } ) ); @@ -576,7 +152,7 @@ void bind_mrpt_obs_CActionRobotMovement3D(std::function< pybind11::module &(std: cl.def_readwrite("mm6DOFModel", &mrpt::obs::CActionRobotMovement3D::TMotionModelOptions::mm6DOFModel); cl.def("assign", (struct mrpt::obs::CActionRobotMovement3D::TMotionModelOptions & (mrpt::obs::CActionRobotMovement3D::TMotionModelOptions::*)(const struct mrpt::obs::CActionRobotMovement3D::TMotionModelOptions &)) &mrpt::obs::CActionRobotMovement3D::TMotionModelOptions::operator=, "C++: mrpt::obs::CActionRobotMovement3D::TMotionModelOptions::operator=(const struct mrpt::obs::CActionRobotMovement3D::TMotionModelOptions &) --> struct mrpt::obs::CActionRobotMovement3D::TMotionModelOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::CActionRobotMovement3D::TMotionModelOptions::TOptions_6DOFModel file:mrpt/obs/CActionRobotMovement3D.h line:71 + { // mrpt::obs::CActionRobotMovement3D::TMotionModelOptions::TOptions_6DOFModel file:mrpt/obs/CActionRobotMovement3D.h line:72 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TOptions_6DOFModel", ""); cl.def( pybind11::init( [](){ return new mrpt::obs::CActionRobotMovement3D::TMotionModelOptions::TOptions_6DOFModel(); } ) ); @@ -600,47 +176,4 @@ void bind_mrpt_obs_CActionRobotMovement3D(std::function< pybind11::module &(std: } } - { // mrpt::obs::CObservation3DScene file:mrpt/obs/CObservation3DScene.h line:28 - pybind11::class_, PyCallBack_mrpt_obs_CObservation3DScene, mrpt::obs::CObservation, mrpt::opengl::Visualizable> cl(M("mrpt::obs"), "CObservation3DScene", "Not a real sensor observation, it stores a 3D scene which can be used for\n debugging or any other logging purposes.\n If stored in a .rawlog file, RawLogViewer will show the contents of\n the scene's main viewport when selecting it on the tree view.\n\n \n CObservation\n \n\n\n \n (New in MRPT 2.3.1)"); - cl.def( pybind11::init( [](){ return new mrpt::obs::CObservation3DScene(); }, [](){ return new PyCallBack_mrpt_obs_CObservation3DScene(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservation3DScene const &o){ return new PyCallBack_mrpt_obs_CObservation3DScene(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::CObservation3DScene const &o){ return new mrpt::obs::CObservation3DScene(o); } ) ); - cl.def_readwrite("scene", &mrpt::obs::CObservation3DScene::scene); - cl.def_readwrite("sensorPose", &mrpt::obs::CObservation3DScene::sensorPose); - cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservation3DScene::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservation3DScene::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); - cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservation3DScene::*)() const) &mrpt::obs::CObservation3DScene::GetRuntimeClass, "C++: mrpt::obs::CObservation3DScene::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); - cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservation3DScene::*)() const) &mrpt::obs::CObservation3DScene::clone, "C++: mrpt::obs::CObservation3DScene::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); - cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservation3DScene::CreateObject, "C++: mrpt::obs::CObservation3DScene::CreateObject() --> class std::shared_ptr"); - cl.def("getSensorPose", (void (mrpt::obs::CObservation3DScene::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservation3DScene::getSensorPose, "C++: mrpt::obs::CObservation3DScene::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); - cl.def("setSensorPose", (void (mrpt::obs::CObservation3DScene::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservation3DScene::setSensorPose, "C++: mrpt::obs::CObservation3DScene::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); - cl.def("getVisualizationInto", (void (mrpt::obs::CObservation3DScene::*)(class mrpt::opengl::CSetOfObjects &) const) &mrpt::obs::CObservation3DScene::getVisualizationInto, "C++: mrpt::obs::CObservation3DScene::getVisualizationInto(class mrpt::opengl::CSetOfObjects &) const --> void", pybind11::arg("o")); - cl.def("assign", (class mrpt::obs::CObservation3DScene & (mrpt::obs::CObservation3DScene::*)(const class mrpt::obs::CObservation3DScene &)) &mrpt::obs::CObservation3DScene::operator=, "C++: mrpt::obs::CObservation3DScene::operator=(const class mrpt::obs::CObservation3DScene &) --> class mrpt::obs::CObservation3DScene &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - { // mrpt::obs::CObservation6DFeatures file:mrpt/obs/CObservation6DFeatures.h line:26 - pybind11::class_, PyCallBack_mrpt_obs_CObservation6DFeatures, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservation6DFeatures", "An observation of one or more \"features\" or \"objects\", possibly identified\n with a unique ID, whose relative SE(3) pose is observed with respect to the\n sensor.\n The list of features is stored in \n \n\n CObservation\n \n\n\n "); - cl.def( pybind11::init( [](){ return new mrpt::obs::CObservation6DFeatures(); }, [](){ return new PyCallBack_mrpt_obs_CObservation6DFeatures(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservation6DFeatures const &o){ return new PyCallBack_mrpt_obs_CObservation6DFeatures(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::CObservation6DFeatures const &o){ return new mrpt::obs::CObservation6DFeatures(o); } ) ); - cl.def_readwrite("minSensorDistance", &mrpt::obs::CObservation6DFeatures::minSensorDistance); - cl.def_readwrite("maxSensorDistance", &mrpt::obs::CObservation6DFeatures::maxSensorDistance); - cl.def_readwrite("sensedFeatures", &mrpt::obs::CObservation6DFeatures::sensedFeatures); - cl.def_readwrite("sensorPose", &mrpt::obs::CObservation6DFeatures::sensorPose); - cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservation6DFeatures::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservation6DFeatures::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); - cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservation6DFeatures::*)() const) &mrpt::obs::CObservation6DFeatures::GetRuntimeClass, "C++: mrpt::obs::CObservation6DFeatures::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); - cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservation6DFeatures::*)() const) &mrpt::obs::CObservation6DFeatures::clone, "C++: mrpt::obs::CObservation6DFeatures::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); - cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservation6DFeatures::CreateObject, "C++: mrpt::obs::CObservation6DFeatures::CreateObject() --> class std::shared_ptr"); - cl.def("getSensorPose", (void (mrpt::obs::CObservation6DFeatures::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservation6DFeatures::getSensorPose, "C++: mrpt::obs::CObservation6DFeatures::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); - cl.def("setSensorPose", (void (mrpt::obs::CObservation6DFeatures::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservation6DFeatures::setSensorPose, "C++: mrpt::obs::CObservation6DFeatures::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); - cl.def("assign", (class mrpt::obs::CObservation6DFeatures & (mrpt::obs::CObservation6DFeatures::*)(const class mrpt::obs::CObservation6DFeatures &)) &mrpt::obs::CObservation6DFeatures::operator=, "C++: mrpt::obs::CObservation6DFeatures::operator=(const class mrpt::obs::CObservation6DFeatures &) --> class mrpt::obs::CObservation6DFeatures &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::CObservation6DFeatures::TMeasurement file:mrpt/obs/CObservation6DFeatures.h line:37 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "TMeasurement", "Each one of the measurements "); - cl.def( pybind11::init( [](){ return new mrpt::obs::CObservation6DFeatures::TMeasurement(); } ) ); - cl.def_readwrite("pose", &mrpt::obs::CObservation6DFeatures::TMeasurement::pose); - cl.def_readwrite("id", &mrpt::obs::CObservation6DFeatures::TMeasurement::id); - cl.def_readwrite("inf_matrix", &mrpt::obs::CObservation6DFeatures::TMeasurement::inf_matrix); - } - - } } diff --git a/python/src/mrpt/obs/CObservationBatteryState.cpp b/python/src/mrpt/obs/CObservation3DScene.cpp similarity index 81% rename from python/src/mrpt/obs/CObservationBatteryState.cpp rename to python/src/mrpt/obs/CObservation3DScene.cpp index 65ecdc50e0..80370fe15f 100644 --- a/python/src/mrpt/obs/CObservationBatteryState.cpp +++ b/python/src/mrpt/obs/CObservation3DScene.cpp @@ -1,12 +1,21 @@ +#include #include +#include #include +#include #include +#include #include +#include +#include +#include #include +#include #include #include #include #include +#include #include #include #include @@ -15,16 +24,24 @@ #include #include #include +#include +#include #include #include -#include -#include +#include +#include +#include #include #include +#include #include #include +#include #include +#include #include +#include +#include #include #include #include @@ -36,7 +53,12 @@ #include // __str__ #include #include +#include +#include +#include +#include #include +#include #include #include @@ -51,13 +73,13 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::CObservationBatteryState file:mrpt/obs/CObservationBatteryState.h line:31 -struct PyCallBack_mrpt_obs_CObservationBatteryState : public mrpt::obs::CObservationBatteryState { - using mrpt::obs::CObservationBatteryState::CObservationBatteryState; +// mrpt::obs::CObservation3DScene file:mrpt/obs/CObservation3DScene.h line:28 +struct PyCallBack_mrpt_obs_CObservation3DScene : public mrpt::obs::CObservation3DScene { + using mrpt::obs::CObservation3DScene::CObservation3DScene; const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -66,11 +88,11 @@ struct PyCallBack_mrpt_obs_CObservationBatteryState : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBatteryState::GetRuntimeClass(); + return CObservation3DScene::GetRuntimeClass(); } class mrpt::rtti::CObject * clone() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -79,11 +101,11 @@ struct PyCallBack_mrpt_obs_CObservationBatteryState : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBatteryState::clone(); + return CObservation3DScene::clone(); } uint8_t serializeGetVersion() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -92,11 +114,11 @@ struct PyCallBack_mrpt_obs_CObservationBatteryState : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBatteryState::serializeGetVersion(); + return CObservation3DScene::serializeGetVersion(); } void serializeTo(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -105,11 +127,11 @@ struct PyCallBack_mrpt_obs_CObservationBatteryState : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBatteryState::serializeTo(a0); + return CObservation3DScene::serializeTo(a0); } void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); if (overload) { auto o = overload.operator()(a0, a1); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -118,11 +140,11 @@ struct PyCallBack_mrpt_obs_CObservationBatteryState : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBatteryState::serializeFrom(a0, a1); + return CObservation3DScene::serializeFrom(a0, a1); } void getSensorPose(class mrpt::poses::CPose3D & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -131,11 +153,11 @@ struct PyCallBack_mrpt_obs_CObservationBatteryState : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBatteryState::getSensorPose(a0); + return CObservation3DScene::getSensorPose(a0); } void setSensorPose(const class mrpt::poses::CPose3D & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -144,24 +166,38 @@ struct PyCallBack_mrpt_obs_CObservationBatteryState : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBatteryState::setSensorPose(a0); + return CObservation3DScene::setSensorPose(a0); } - bool exportTxtSupported() const override { + void getVisualizationInto(class mrpt::opengl::CSetOfObjects & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getVisualizationInto"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation3DScene::getVisualizationInto(a0); + } + using _binder_ret_0 = mrpt::Clock::time_point; + _binder_ret_0 getOriginalReceivedTimeStamp() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { + static pybind11::detail::override_caster_t<_binder_ret_0> caster; + return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); } - return CObservationBatteryState::exportTxtSupported(); + return CObservation::getOriginalReceivedTimeStamp(); } - std::string exportTxtHeader() const override { + std::string asString() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -170,38 +206,37 @@ struct PyCallBack_mrpt_obs_CObservationBatteryState : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBatteryState::exportTxtHeader(); + return CObservation::asString(); } - std::string exportTxtDataRow() const override { + bool exportTxtSupported() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBatteryState::exportTxtDataRow(); + return CObservation::exportTxtSupported(); } - using _binder_ret_0 = mrpt::Clock::time_point; - _binder_ret_0 getOriginalReceivedTimeStamp() const override { + std::string exportTxtHeader() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { - static pybind11::detail::override_caster_t<_binder_ret_0> caster; - return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::getOriginalReceivedTimeStamp(); + return CObservation::exportTxtHeader(); } - std::string asString() const override { + std::string exportTxtDataRow() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -210,11 +245,11 @@ struct PyCallBack_mrpt_obs_CObservationBatteryState : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::asString(); + return CObservation::exportTxtDataRow(); } void unload() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -227,7 +262,7 @@ struct PyCallBack_mrpt_obs_CObservationBatteryState : public mrpt::obs::CObserva } void load_impl() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -240,13 +275,13 @@ struct PyCallBack_mrpt_obs_CObservationBatteryState : public mrpt::obs::CObserva } }; -// mrpt::obs::CObservationBeaconRanges file:mrpt/obs/CObservationBeaconRanges.h line:24 -struct PyCallBack_mrpt_obs_CObservationBeaconRanges : public mrpt::obs::CObservationBeaconRanges { - using mrpt::obs::CObservationBeaconRanges::CObservationBeaconRanges; +// mrpt::obs::CObservation6DFeatures file:mrpt/obs/CObservation6DFeatures.h line:26 +struct PyCallBack_mrpt_obs_CObservation6DFeatures : public mrpt::obs::CObservation6DFeatures { + using mrpt::obs::CObservation6DFeatures::CObservation6DFeatures; const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -255,11 +290,11 @@ struct PyCallBack_mrpt_obs_CObservationBeaconRanges : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBeaconRanges::GetRuntimeClass(); + return CObservation6DFeatures::GetRuntimeClass(); } class mrpt::rtti::CObject * clone() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -268,11 +303,11 @@ struct PyCallBack_mrpt_obs_CObservationBeaconRanges : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBeaconRanges::clone(); + return CObservation6DFeatures::clone(); } uint8_t serializeGetVersion() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -281,11 +316,11 @@ struct PyCallBack_mrpt_obs_CObservationBeaconRanges : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBeaconRanges::serializeGetVersion(); + return CObservation6DFeatures::serializeGetVersion(); } void serializeTo(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -294,11 +329,11 @@ struct PyCallBack_mrpt_obs_CObservationBeaconRanges : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBeaconRanges::serializeTo(a0); + return CObservation6DFeatures::serializeTo(a0); } void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); if (overload) { auto o = overload.operator()(a0, a1); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -307,11 +342,11 @@ struct PyCallBack_mrpt_obs_CObservationBeaconRanges : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBeaconRanges::serializeFrom(a0, a1); + return CObservation6DFeatures::serializeFrom(a0, a1); } void getSensorPose(class mrpt::poses::CPose3D & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -320,11 +355,11 @@ struct PyCallBack_mrpt_obs_CObservationBeaconRanges : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBeaconRanges::getSensorPose(a0); + return CObservation6DFeatures::getSensorPose(a0); } void setSensorPose(const class mrpt::poses::CPose3D & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -333,24 +368,25 @@ struct PyCallBack_mrpt_obs_CObservationBeaconRanges : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBeaconRanges::setSensorPose(a0); + return CObservation6DFeatures::setSensorPose(a0); } - bool exportTxtSupported() const override { + using _binder_ret_0 = mrpt::Clock::time_point; + _binder_ret_0 getOriginalReceivedTimeStamp() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { + static pybind11::detail::override_caster_t<_binder_ret_0> caster; + return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); } - return CObservationBeaconRanges::exportTxtSupported(); + return CObservation::getOriginalReceivedTimeStamp(); } - std::string exportTxtHeader() const override { + std::string asString() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -359,38 +395,37 @@ struct PyCallBack_mrpt_obs_CObservationBeaconRanges : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBeaconRanges::exportTxtHeader(); + return CObservation::asString(); } - std::string exportTxtDataRow() const override { + bool exportTxtSupported() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBeaconRanges::exportTxtDataRow(); + return CObservation::exportTxtSupported(); } - using _binder_ret_0 = mrpt::Clock::time_point; - _binder_ret_0 getOriginalReceivedTimeStamp() const override { + std::string exportTxtHeader() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { - static pybind11::detail::override_caster_t<_binder_ret_0> caster; - return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::getOriginalReceivedTimeStamp(); + return CObservation::exportTxtHeader(); } - std::string asString() const override { + std::string exportTxtDataRow() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -399,11 +434,11 @@ struct PyCallBack_mrpt_obs_CObservationBeaconRanges : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::asString(); + return CObservation::exportTxtDataRow(); } void unload() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -416,7 +451,7 @@ struct PyCallBack_mrpt_obs_CObservationBeaconRanges : public mrpt::obs::CObserva } void load_impl() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -429,13 +464,13 @@ struct PyCallBack_mrpt_obs_CObservationBeaconRanges : public mrpt::obs::CObserva } }; -// mrpt::obs::CObservationBearingRange file:mrpt/obs/CObservationBearingRange.h line:28 -struct PyCallBack_mrpt_obs_CObservationBearingRange : public mrpt::obs::CObservationBearingRange { - using mrpt::obs::CObservationBearingRange::CObservationBearingRange; +// mrpt::obs::CObservationBatteryState file:mrpt/obs/CObservationBatteryState.h line:31 +struct PyCallBack_mrpt_obs_CObservationBatteryState : public mrpt::obs::CObservationBatteryState { + using mrpt::obs::CObservationBatteryState::CObservationBatteryState; const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -444,11 +479,11 @@ struct PyCallBack_mrpt_obs_CObservationBearingRange : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBearingRange::GetRuntimeClass(); + return CObservationBatteryState::GetRuntimeClass(); } class mrpt::rtti::CObject * clone() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -457,11 +492,11 @@ struct PyCallBack_mrpt_obs_CObservationBearingRange : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBearingRange::clone(); + return CObservationBatteryState::clone(); } uint8_t serializeGetVersion() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -470,11 +505,11 @@ struct PyCallBack_mrpt_obs_CObservationBearingRange : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBearingRange::serializeGetVersion(); + return CObservationBatteryState::serializeGetVersion(); } void serializeTo(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -483,11 +518,11 @@ struct PyCallBack_mrpt_obs_CObservationBearingRange : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBearingRange::serializeTo(a0); + return CObservationBatteryState::serializeTo(a0); } void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); if (overload) { auto o = overload.operator()(a0, a1); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -496,11 +531,11 @@ struct PyCallBack_mrpt_obs_CObservationBearingRange : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBearingRange::serializeFrom(a0, a1); + return CObservationBatteryState::serializeFrom(a0, a1); } void getSensorPose(class mrpt::poses::CPose3D & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -509,11 +544,11 @@ struct PyCallBack_mrpt_obs_CObservationBearingRange : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBearingRange::getSensorPose(a0); + return CObservationBatteryState::getSensorPose(a0); } void setSensorPose(const class mrpt::poses::CPose3D & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -522,25 +557,24 @@ struct PyCallBack_mrpt_obs_CObservationBearingRange : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationBearingRange::setSensorPose(a0); + return CObservationBatteryState::setSensorPose(a0); } - using _binder_ret_0 = mrpt::Clock::time_point; - _binder_ret_0 getOriginalReceivedTimeStamp() const override { + bool exportTxtSupported() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { - static pybind11::detail::override_caster_t<_binder_ret_0> caster; - return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::getOriginalReceivedTimeStamp(); + return CObservationBatteryState::exportTxtSupported(); } - std::string asString() const override { + std::string exportTxtHeader() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -549,37 +583,38 @@ struct PyCallBack_mrpt_obs_CObservationBearingRange : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::asString(); + return CObservationBatteryState::exportTxtHeader(); } - bool exportTxtSupported() const override { + std::string exportTxtDataRow() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::exportTxtSupported(); + return CObservationBatteryState::exportTxtDataRow(); } - std::string exportTxtHeader() const override { + using _binder_ret_0 = mrpt::Clock::time_point; + _binder_ret_0 getOriginalReceivedTimeStamp() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { + static pybind11::detail::override_caster_t<_binder_ret_0> caster; + return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); } - return CObservation::exportTxtHeader(); + return CObservation::getOriginalReceivedTimeStamp(); } - std::string exportTxtDataRow() const override { + std::string asString() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -588,11 +623,11 @@ struct PyCallBack_mrpt_obs_CObservationBearingRange : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::exportTxtDataRow(); + return CObservation::asString(); } void unload() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -605,7 +640,7 @@ struct PyCallBack_mrpt_obs_CObservationBearingRange : public mrpt::obs::CObserva } void load_impl() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -618,13 +653,13 @@ struct PyCallBack_mrpt_obs_CObservationBearingRange : public mrpt::obs::CObserva } }; -// mrpt::obs::CObservationComment file:mrpt/obs/CObservationComment.h line:24 -struct PyCallBack_mrpt_obs_CObservationComment : public mrpt::obs::CObservationComment { - using mrpt::obs::CObservationComment::CObservationComment; +// mrpt::obs::CObservationBeaconRanges file:mrpt/obs/CObservationBeaconRanges.h line:24 +struct PyCallBack_mrpt_obs_CObservationBeaconRanges : public mrpt::obs::CObservationBeaconRanges { + using mrpt::obs::CObservationBeaconRanges::CObservationBeaconRanges; const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -633,11 +668,11 @@ struct PyCallBack_mrpt_obs_CObservationComment : public mrpt::obs::CObservationC } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationComment::GetRuntimeClass(); + return CObservationBeaconRanges::GetRuntimeClass(); } class mrpt::rtti::CObject * clone() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -646,11 +681,11 @@ struct PyCallBack_mrpt_obs_CObservationComment : public mrpt::obs::CObservationC } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationComment::clone(); + return CObservationBeaconRanges::clone(); } uint8_t serializeGetVersion() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -659,11 +694,11 @@ struct PyCallBack_mrpt_obs_CObservationComment : public mrpt::obs::CObservationC } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationComment::serializeGetVersion(); + return CObservationBeaconRanges::serializeGetVersion(); } void serializeTo(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -672,11 +707,11 @@ struct PyCallBack_mrpt_obs_CObservationComment : public mrpt::obs::CObservationC } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationComment::serializeTo(a0); + return CObservationBeaconRanges::serializeTo(a0); } void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); if (overload) { auto o = overload.operator()(a0, a1); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -685,11 +720,11 @@ struct PyCallBack_mrpt_obs_CObservationComment : public mrpt::obs::CObservationC } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationComment::serializeFrom(a0, a1); + return CObservationBeaconRanges::serializeFrom(a0, a1); } void getSensorPose(class mrpt::poses::CPose3D & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -698,11 +733,11 @@ struct PyCallBack_mrpt_obs_CObservationComment : public mrpt::obs::CObservationC } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationComment::getSensorPose(a0); + return CObservationBeaconRanges::getSensorPose(a0); } void setSensorPose(const class mrpt::poses::CPose3D & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -711,25 +746,24 @@ struct PyCallBack_mrpt_obs_CObservationComment : public mrpt::obs::CObservationC } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationComment::setSensorPose(a0); + return CObservationBeaconRanges::setSensorPose(a0); } - using _binder_ret_0 = mrpt::Clock::time_point; - _binder_ret_0 getOriginalReceivedTimeStamp() const override { + bool exportTxtSupported() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { - static pybind11::detail::override_caster_t<_binder_ret_0> caster; - return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::getOriginalReceivedTimeStamp(); + return CObservationBeaconRanges::exportTxtSupported(); } - std::string asString() const override { + std::string exportTxtHeader() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -738,37 +772,38 @@ struct PyCallBack_mrpt_obs_CObservationComment : public mrpt::obs::CObservationC } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::asString(); + return CObservationBeaconRanges::exportTxtHeader(); } - bool exportTxtSupported() const override { + std::string exportTxtDataRow() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::exportTxtSupported(); + return CObservationBeaconRanges::exportTxtDataRow(); } - std::string exportTxtHeader() const override { + using _binder_ret_0 = mrpt::Clock::time_point; + _binder_ret_0 getOriginalReceivedTimeStamp() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { + static pybind11::detail::override_caster_t<_binder_ret_0> caster; + return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); } - return CObservation::exportTxtHeader(); + return CObservation::getOriginalReceivedTimeStamp(); } - std::string exportTxtDataRow() const override { + std::string asString() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -777,11 +812,11 @@ struct PyCallBack_mrpt_obs_CObservationComment : public mrpt::obs::CObservationC } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::exportTxtDataRow(); + return CObservation::asString(); } void unload() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -794,7 +829,7 @@ struct PyCallBack_mrpt_obs_CObservationComment : public mrpt::obs::CObservationC } void load_impl() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -807,8 +842,51 @@ struct PyCallBack_mrpt_obs_CObservationComment : public mrpt::obs::CObservationC } }; -void bind_mrpt_obs_CObservationBatteryState(std::function< pybind11::module &(std::string const &namespace_) > &M) +void bind_mrpt_obs_CObservation3DScene(std::function< pybind11::module &(std::string const &namespace_) > &M) { + { // mrpt::obs::CObservation3DScene file:mrpt/obs/CObservation3DScene.h line:28 + pybind11::class_, PyCallBack_mrpt_obs_CObservation3DScene, mrpt::obs::CObservation, mrpt::opengl::Visualizable> cl(M("mrpt::obs"), "CObservation3DScene", "Not a real sensor observation, it stores a 3D scene which can be used for\n debugging or any other logging purposes.\n If stored in a .rawlog file, RawLogViewer will show the contents of\n the scene's main viewport when selecting it on the tree view.\n\n \n CObservation\n \n\n\n \n (New in MRPT 2.3.1)"); + cl.def( pybind11::init( [](){ return new mrpt::obs::CObservation3DScene(); }, [](){ return new PyCallBack_mrpt_obs_CObservation3DScene(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservation3DScene const &o){ return new PyCallBack_mrpt_obs_CObservation3DScene(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::CObservation3DScene const &o){ return new mrpt::obs::CObservation3DScene(o); } ) ); + cl.def_readwrite("scene", &mrpt::obs::CObservation3DScene::scene); + cl.def_readwrite("sensorPose", &mrpt::obs::CObservation3DScene::sensorPose); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservation3DScene::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservation3DScene::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservation3DScene::*)() const) &mrpt::obs::CObservation3DScene::GetRuntimeClass, "C++: mrpt::obs::CObservation3DScene::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservation3DScene::*)() const) &mrpt::obs::CObservation3DScene::clone, "C++: mrpt::obs::CObservation3DScene::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservation3DScene::CreateObject, "C++: mrpt::obs::CObservation3DScene::CreateObject() --> class std::shared_ptr"); + cl.def("getSensorPose", (void (mrpt::obs::CObservation3DScene::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservation3DScene::getSensorPose, "C++: mrpt::obs::CObservation3DScene::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); + cl.def("setSensorPose", (void (mrpt::obs::CObservation3DScene::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservation3DScene::setSensorPose, "C++: mrpt::obs::CObservation3DScene::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); + cl.def("getVisualizationInto", (void (mrpt::obs::CObservation3DScene::*)(class mrpt::opengl::CSetOfObjects &) const) &mrpt::obs::CObservation3DScene::getVisualizationInto, "C++: mrpt::obs::CObservation3DScene::getVisualizationInto(class mrpt::opengl::CSetOfObjects &) const --> void", pybind11::arg("o")); + cl.def("assign", (class mrpt::obs::CObservation3DScene & (mrpt::obs::CObservation3DScene::*)(const class mrpt::obs::CObservation3DScene &)) &mrpt::obs::CObservation3DScene::operator=, "C++: mrpt::obs::CObservation3DScene::operator=(const class mrpt::obs::CObservation3DScene &) --> class mrpt::obs::CObservation3DScene &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::obs::CObservation6DFeatures file:mrpt/obs/CObservation6DFeatures.h line:26 + pybind11::class_, PyCallBack_mrpt_obs_CObservation6DFeatures, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservation6DFeatures", "An observation of one or more \"features\" or \"objects\", possibly identified\n with a unique ID, whose relative SE(3) pose is observed with respect to the\n sensor.\n The list of features is stored in \n \n\n CObservation\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CObservation6DFeatures(); }, [](){ return new PyCallBack_mrpt_obs_CObservation6DFeatures(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservation6DFeatures const &o){ return new PyCallBack_mrpt_obs_CObservation6DFeatures(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::CObservation6DFeatures const &o){ return new mrpt::obs::CObservation6DFeatures(o); } ) ); + cl.def_readwrite("minSensorDistance", &mrpt::obs::CObservation6DFeatures::minSensorDistance); + cl.def_readwrite("maxSensorDistance", &mrpt::obs::CObservation6DFeatures::maxSensorDistance); + cl.def_readwrite("sensedFeatures", &mrpt::obs::CObservation6DFeatures::sensedFeatures); + cl.def_readwrite("sensorPose", &mrpt::obs::CObservation6DFeatures::sensorPose); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservation6DFeatures::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservation6DFeatures::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservation6DFeatures::*)() const) &mrpt::obs::CObservation6DFeatures::GetRuntimeClass, "C++: mrpt::obs::CObservation6DFeatures::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservation6DFeatures::*)() const) &mrpt::obs::CObservation6DFeatures::clone, "C++: mrpt::obs::CObservation6DFeatures::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservation6DFeatures::CreateObject, "C++: mrpt::obs::CObservation6DFeatures::CreateObject() --> class std::shared_ptr"); + cl.def("getSensorPose", (void (mrpt::obs::CObservation6DFeatures::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservation6DFeatures::getSensorPose, "C++: mrpt::obs::CObservation6DFeatures::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); + cl.def("setSensorPose", (void (mrpt::obs::CObservation6DFeatures::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservation6DFeatures::setSensorPose, "C++: mrpt::obs::CObservation6DFeatures::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); + cl.def("assign", (class mrpt::obs::CObservation6DFeatures & (mrpt::obs::CObservation6DFeatures::*)(const class mrpt::obs::CObservation6DFeatures &)) &mrpt::obs::CObservation6DFeatures::operator=, "C++: mrpt::obs::CObservation6DFeatures::operator=(const class mrpt::obs::CObservation6DFeatures &) --> class mrpt::obs::CObservation6DFeatures &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::CObservation6DFeatures::TMeasurement file:mrpt/obs/CObservation6DFeatures.h line:37 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TMeasurement", "Each one of the measurements "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CObservation6DFeatures::TMeasurement(); } ) ); + cl.def_readwrite("pose", &mrpt::obs::CObservation6DFeatures::TMeasurement::pose); + cl.def_readwrite("id", &mrpt::obs::CObservation6DFeatures::TMeasurement::id); + cl.def_readwrite("inf_matrix", &mrpt::obs::CObservation6DFeatures::TMeasurement::inf_matrix); + } + + } { // mrpt::obs::CObservationBatteryState file:mrpt/obs/CObservationBatteryState.h line:31 pybind11::class_, PyCallBack_mrpt_obs_CObservationBatteryState, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationBatteryState", "This represents a measurement of the batteries on the robot.\n The battery levels are in volts in the form of the public members:\n - voltageMainRobotBattery\n - voltageMainRobotComputer\n - voltageOtherBatteries\n\n There are boolean flags for signaling when the corresponding values have\nbeen filled out or not.\n\n \n CObservation\n \n\n\n "); cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationBatteryState(); }, [](){ return new PyCallBack_mrpt_obs_CObservationBatteryState(); } ) ); @@ -864,54 +942,4 @@ void bind_mrpt_obs_CObservationBatteryState(std::function< pybind11::module &(st } } - { // mrpt::obs::CObservationBearingRange file:mrpt/obs/CObservationBearingRange.h line:28 - pybind11::class_, PyCallBack_mrpt_obs_CObservationBearingRange, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationBearingRange", "This observation represents a number of range-bearing value pairs, each one\n for a detected landmark, which optionally can have identification IDs.\n This class can manage sensors that detect landmarks in a 2D plane (e.g. a\n laser scanner) or in the 3D space (e.g. a camera). There are\n two direction angles: yaw (azimuth) and pitch (negative elevation). For 2D\n sensors, the pitch must be always set to 0.\n See CObservationBearingRange::validCovariances for the instructions to fill\n the uncertainty covariances.\n \n\n CObservation\n \n\n\n "); - cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationBearingRange(); }, [](){ return new PyCallBack_mrpt_obs_CObservationBearingRange(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservationBearingRange const &o){ return new PyCallBack_mrpt_obs_CObservationBearingRange(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::CObservationBearingRange const &o){ return new mrpt::obs::CObservationBearingRange(o); } ) ); - cl.def_readwrite("minSensorDistance", &mrpt::obs::CObservationBearingRange::minSensorDistance); - cl.def_readwrite("maxSensorDistance", &mrpt::obs::CObservationBearingRange::maxSensorDistance); - cl.def_readwrite("fieldOfView_yaw", &mrpt::obs::CObservationBearingRange::fieldOfView_yaw); - cl.def_readwrite("fieldOfView_pitch", &mrpt::obs::CObservationBearingRange::fieldOfView_pitch); - cl.def_readwrite("sensorLocationOnRobot", &mrpt::obs::CObservationBearingRange::sensorLocationOnRobot); - cl.def_readwrite("sensedData", &mrpt::obs::CObservationBearingRange::sensedData); - cl.def_readwrite("validCovariances", &mrpt::obs::CObservationBearingRange::validCovariances); - cl.def_readwrite("sensor_std_range", &mrpt::obs::CObservationBearingRange::sensor_std_range); - cl.def_readwrite("sensor_std_yaw", &mrpt::obs::CObservationBearingRange::sensor_std_yaw); - cl.def_readwrite("sensor_std_pitch", &mrpt::obs::CObservationBearingRange::sensor_std_pitch); - cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservationBearingRange::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservationBearingRange::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); - cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservationBearingRange::*)() const) &mrpt::obs::CObservationBearingRange::GetRuntimeClass, "C++: mrpt::obs::CObservationBearingRange::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); - cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservationBearingRange::*)() const) &mrpt::obs::CObservationBearingRange::clone, "C++: mrpt::obs::CObservationBearingRange::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); - cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservationBearingRange::CreateObject, "C++: mrpt::obs::CObservationBearingRange::CreateObject() --> class std::shared_ptr"); - cl.def("debugPrintOut", (void (mrpt::obs::CObservationBearingRange::*)()) &mrpt::obs::CObservationBearingRange::debugPrintOut, "Prints out the contents of the object.\n\nC++: mrpt::obs::CObservationBearingRange::debugPrintOut() --> void"); - cl.def("getSensorPose", (void (mrpt::obs::CObservationBearingRange::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationBearingRange::getSensorPose, "C++: mrpt::obs::CObservationBearingRange::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); - cl.def("setSensorPose", (void (mrpt::obs::CObservationBearingRange::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationBearingRange::setSensorPose, "C++: mrpt::obs::CObservationBearingRange::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); - cl.def("assign", (class mrpt::obs::CObservationBearingRange & (mrpt::obs::CObservationBearingRange::*)(const class mrpt::obs::CObservationBearingRange &)) &mrpt::obs::CObservationBearingRange::operator=, "C++: mrpt::obs::CObservationBearingRange::operator=(const class mrpt::obs::CObservationBearingRange &) --> class mrpt::obs::CObservationBearingRange &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::CObservationBearingRange::TMeasurement file:mrpt/obs/CObservationBearingRange.h line:51 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "TMeasurement", "Each one of the measurements:"); - cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationBearingRange::TMeasurement(); } ) ); - cl.def_readwrite("range", &mrpt::obs::CObservationBearingRange::TMeasurement::range); - cl.def_readwrite("yaw", &mrpt::obs::CObservationBearingRange::TMeasurement::yaw); - cl.def_readwrite("pitch", &mrpt::obs::CObservationBearingRange::TMeasurement::pitch); - cl.def_readwrite("landmarkID", &mrpt::obs::CObservationBearingRange::TMeasurement::landmarkID); - cl.def_readwrite("covariance", &mrpt::obs::CObservationBearingRange::TMeasurement::covariance); - } - - } - { // mrpt::obs::CObservationComment file:mrpt/obs/CObservationComment.h line:24 - pybind11::class_, PyCallBack_mrpt_obs_CObservationComment, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationComment", "This \"observation\" is actually a placeholder for a text block with comments\n or additional parameters attached to a given rawlog file.\n There should be only one of this observations in a rawlog file, and it's\n recommended to insert/modify them from the application RawlogViewer.\n\n \n CObservation\n \n\n\n "); - cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationComment(); }, [](){ return new PyCallBack_mrpt_obs_CObservationComment(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservationComment const &o){ return new PyCallBack_mrpt_obs_CObservationComment(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::CObservationComment const &o){ return new mrpt::obs::CObservationComment(o); } ) ); - cl.def_readwrite("text", &mrpt::obs::CObservationComment::text); - cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservationComment::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservationComment::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); - cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservationComment::*)() const) &mrpt::obs::CObservationComment::GetRuntimeClass, "C++: mrpt::obs::CObservationComment::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); - cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservationComment::*)() const) &mrpt::obs::CObservationComment::clone, "C++: mrpt::obs::CObservationComment::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); - cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservationComment::CreateObject, "C++: mrpt::obs::CObservationComment::CreateObject() --> class std::shared_ptr"); - cl.def("getSensorPose", (void (mrpt::obs::CObservationComment::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationComment::getSensorPose, "C++: mrpt::obs::CObservationComment::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("")); - cl.def("setSensorPose", (void (mrpt::obs::CObservationComment::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationComment::setSensorPose, "C++: mrpt::obs::CObservationComment::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("")); - cl.def("assign", (class mrpt::obs::CObservationComment & (mrpt::obs::CObservationComment::*)(const class mrpt::obs::CObservationComment &)) &mrpt::obs::CObservationComment::operator=, "C++: mrpt::obs::CObservationComment::operator=(const class mrpt::obs::CObservationComment &) --> class mrpt::obs::CObservationComment &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } } diff --git a/python/src/mrpt/obs/CObservationOdometry.cpp b/python/src/mrpt/obs/CObservationBearingRange.cpp similarity index 76% rename from python/src/mrpt/obs/CObservationOdometry.cpp rename to python/src/mrpt/obs/CObservationBearingRange.cpp index 9fd93df1ad..5d81ef511f 100644 --- a/python/src/mrpt/obs/CObservationOdometry.cpp +++ b/python/src/mrpt/obs/CObservationBearingRange.cpp @@ -2,11 +2,7 @@ #include #include #include -#include -#include -#include #include -#include #include #include #include @@ -19,10 +15,10 @@ #include #include #include +#include +#include #include #include -#include -#include #include #include #include @@ -33,7 +29,6 @@ #include #include #include -#include #include #include #include @@ -41,9 +36,7 @@ #include // __str__ #include #include -#include #include -#include #include #include @@ -58,13 +51,13 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::CObservationOdometry file:mrpt/obs/CObservationOdometry.h line:32 -struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservationOdometry { - using mrpt::obs::CObservationOdometry::CObservationOdometry; +// mrpt::obs::CObservationBearingRange file:mrpt/obs/CObservationBearingRange.h line:28 +struct PyCallBack_mrpt_obs_CObservationBearingRange : public mrpt::obs::CObservationBearingRange { + using mrpt::obs::CObservationBearingRange::CObservationBearingRange; const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -73,11 +66,11 @@ struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservation } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationOdometry::GetRuntimeClass(); + return CObservationBearingRange::GetRuntimeClass(); } class mrpt::rtti::CObject * clone() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -86,11 +79,11 @@ struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservation } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationOdometry::clone(); + return CObservationBearingRange::clone(); } uint8_t serializeGetVersion() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -99,11 +92,11 @@ struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservation } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationOdometry::serializeGetVersion(); + return CObservationBearingRange::serializeGetVersion(); } void serializeTo(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -112,11 +105,11 @@ struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservation } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationOdometry::serializeTo(a0); + return CObservationBearingRange::serializeTo(a0); } void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); if (overload) { auto o = overload.operator()(a0, a1); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -125,11 +118,11 @@ struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservation } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationOdometry::serializeFrom(a0, a1); + return CObservationBearingRange::serializeFrom(a0, a1); } void getSensorPose(class mrpt::poses::CPose3D & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -138,11 +131,11 @@ struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservation } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationOdometry::getSensorPose(a0); + return CObservationBearingRange::getSensorPose(a0); } void setSensorPose(const class mrpt::poses::CPose3D & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -151,24 +144,25 @@ struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservation } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationOdometry::setSensorPose(a0); + return CObservationBearingRange::setSensorPose(a0); } - bool exportTxtSupported() const override { + using _binder_ret_0 = mrpt::Clock::time_point; + _binder_ret_0 getOriginalReceivedTimeStamp() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { + static pybind11::detail::override_caster_t<_binder_ret_0> caster; + return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); } - return CObservationOdometry::exportTxtSupported(); + return CObservation::getOriginalReceivedTimeStamp(); } - std::string exportTxtHeader() const override { + std::string asString() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -177,38 +171,37 @@ struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservation } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationOdometry::exportTxtHeader(); + return CObservation::asString(); } - std::string exportTxtDataRow() const override { + bool exportTxtSupported() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationOdometry::exportTxtDataRow(); + return CObservation::exportTxtSupported(); } - using _binder_ret_0 = mrpt::Clock::time_point; - _binder_ret_0 getOriginalReceivedTimeStamp() const override { + std::string exportTxtHeader() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { - static pybind11::detail::override_caster_t<_binder_ret_0> caster; - return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::getOriginalReceivedTimeStamp(); + return CObservation::exportTxtHeader(); } - std::string asString() const override { + std::string exportTxtDataRow() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -217,11 +210,11 @@ struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservation } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::asString(); + return CObservation::exportTxtDataRow(); } void unload() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -234,7 +227,7 @@ struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservation } void load_impl() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -247,13 +240,13 @@ struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservation } }; -// mrpt::obs::CObservationReflectivity file:mrpt/obs/CObservationReflectivity.h line:24 -struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObservationReflectivity { - using mrpt::obs::CObservationReflectivity::CObservationReflectivity; +// mrpt::obs::CObservationComment file:mrpt/obs/CObservationComment.h line:24 +struct PyCallBack_mrpt_obs_CObservationComment : public mrpt::obs::CObservationComment { + using mrpt::obs::CObservationComment::CObservationComment; const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -262,11 +255,11 @@ struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationReflectivity::GetRuntimeClass(); + return CObservationComment::GetRuntimeClass(); } class mrpt::rtti::CObject * clone() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -275,11 +268,11 @@ struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationReflectivity::clone(); + return CObservationComment::clone(); } uint8_t serializeGetVersion() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -288,11 +281,11 @@ struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationReflectivity::serializeGetVersion(); + return CObservationComment::serializeGetVersion(); } void serializeTo(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -301,11 +294,11 @@ struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationReflectivity::serializeTo(a0); + return CObservationComment::serializeTo(a0); } void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); if (overload) { auto o = overload.operator()(a0, a1); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -314,11 +307,11 @@ struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationReflectivity::serializeFrom(a0, a1); + return CObservationComment::serializeFrom(a0, a1); } void getSensorPose(class mrpt::poses::CPose3D & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -327,11 +320,11 @@ struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationReflectivity::getSensorPose(a0); + return CObservationComment::getSensorPose(a0); } void setSensorPose(const class mrpt::poses::CPose3D & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -340,24 +333,25 @@ struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationReflectivity::setSensorPose(a0); + return CObservationComment::setSensorPose(a0); } - bool exportTxtSupported() const override { + using _binder_ret_0 = mrpt::Clock::time_point; + _binder_ret_0 getOriginalReceivedTimeStamp() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { + static pybind11::detail::override_caster_t<_binder_ret_0> caster; + return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); } - return CObservationReflectivity::exportTxtSupported(); + return CObservation::getOriginalReceivedTimeStamp(); } - std::string exportTxtHeader() const override { + std::string asString() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -366,38 +360,37 @@ struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationReflectivity::exportTxtHeader(); + return CObservation::asString(); } - std::string exportTxtDataRow() const override { + bool exportTxtSupported() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationReflectivity::exportTxtDataRow(); + return CObservation::exportTxtSupported(); } - using _binder_ret_0 = mrpt::Clock::time_point; - _binder_ret_0 getOriginalReceivedTimeStamp() const override { + std::string exportTxtHeader() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { - static pybind11::detail::override_caster_t<_binder_ret_0> caster; - return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::getOriginalReceivedTimeStamp(); + return CObservation::exportTxtHeader(); } - std::string asString() const override { + std::string exportTxtDataRow() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -406,11 +399,11 @@ struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObserva } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::asString(); + return CObservation::exportTxtDataRow(); } void unload() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -423,7 +416,7 @@ struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObserva } void load_impl() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -436,13 +429,13 @@ struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObserva } }; -// mrpt::obs::CObservationRobotPose file:mrpt/obs/CObservationRobotPose.h line:21 -struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservationRobotPose { - using mrpt::obs::CObservationRobotPose::CObservationRobotPose; +// mrpt::obs::CObservationOdometry file:mrpt/obs/CObservationOdometry.h line:32 +struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservationOdometry { + using mrpt::obs::CObservationOdometry::CObservationOdometry; const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -451,11 +444,11 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationRobotPose::GetRuntimeClass(); + return CObservationOdometry::GetRuntimeClass(); } class mrpt::rtti::CObject * clone() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -464,11 +457,11 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationRobotPose::clone(); + return CObservationOdometry::clone(); } uint8_t serializeGetVersion() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -477,11 +470,11 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationRobotPose::serializeGetVersion(); + return CObservationOdometry::serializeGetVersion(); } void serializeTo(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -490,11 +483,11 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationRobotPose::serializeTo(a0); + return CObservationOdometry::serializeTo(a0); } void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); if (overload) { auto o = overload.operator()(a0, a1); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -503,11 +496,11 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationRobotPose::serializeFrom(a0, a1); + return CObservationOdometry::serializeFrom(a0, a1); } void getSensorPose(class mrpt::poses::CPose3D & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -516,11 +509,11 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationRobotPose::getSensorPose(a0); + return CObservationOdometry::getSensorPose(a0); } void setSensorPose(const class mrpt::poses::CPose3D & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -529,11 +522,11 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationRobotPose::setSensorPose(a0); + return CObservationOdometry::setSensorPose(a0); } bool exportTxtSupported() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -542,11 +535,11 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationRobotPose::exportTxtSupported(); + return CObservationOdometry::exportTxtSupported(); } std::string exportTxtHeader() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -555,11 +548,11 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationRobotPose::exportTxtHeader(); + return CObservationOdometry::exportTxtHeader(); } std::string exportTxtDataRow() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -568,12 +561,12 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationRobotPose::exportTxtDataRow(); + return CObservationOdometry::exportTxtDataRow(); } using _binder_ret_0 = mrpt::Clock::time_point; _binder_ret_0 getOriginalReceivedTimeStamp() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { @@ -586,7 +579,7 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } std::string asString() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -599,7 +592,7 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } void unload() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -612,7 +605,7 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } void load_impl() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -625,13 +618,13 @@ struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservatio } }; -// mrpt::obs::CObservationStereoImagesFeatures file:mrpt/obs/CObservationStereoImagesFeatures.h line:36 -struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs::CObservationStereoImagesFeatures { - using mrpt::obs::CObservationStereoImagesFeatures::CObservationStereoImagesFeatures; +// mrpt::obs::CObservationReflectivity file:mrpt/obs/CObservationReflectivity.h line:24 +struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObservationReflectivity { + using mrpt::obs::CObservationReflectivity::CObservationReflectivity; const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -640,11 +633,11 @@ struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs:: } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationStereoImagesFeatures::GetRuntimeClass(); + return CObservationReflectivity::GetRuntimeClass(); } class mrpt::rtti::CObject * clone() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -653,11 +646,11 @@ struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs:: } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationStereoImagesFeatures::clone(); + return CObservationReflectivity::clone(); } uint8_t serializeGetVersion() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -666,11 +659,11 @@ struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs:: } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationStereoImagesFeatures::serializeGetVersion(); + return CObservationReflectivity::serializeGetVersion(); } void serializeTo(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -679,11 +672,11 @@ struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs:: } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationStereoImagesFeatures::serializeTo(a0); + return CObservationReflectivity::serializeTo(a0); } void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); if (overload) { auto o = overload.operator()(a0, a1); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -692,11 +685,11 @@ struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs:: } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationStereoImagesFeatures::serializeFrom(a0, a1); + return CObservationReflectivity::serializeFrom(a0, a1); } void getSensorPose(class mrpt::poses::CPose3D & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -705,11 +698,11 @@ struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs:: } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationStereoImagesFeatures::getSensorPose(a0); + return CObservationReflectivity::getSensorPose(a0); } void setSensorPose(const class mrpt::poses::CPose3D & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -718,25 +711,24 @@ struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs:: } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservationStereoImagesFeatures::setSensorPose(a0); + return CObservationReflectivity::setSensorPose(a0); } - using _binder_ret_0 = mrpt::Clock::time_point; - _binder_ret_0 getOriginalReceivedTimeStamp() const override { + bool exportTxtSupported() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { - static pybind11::detail::override_caster_t<_binder_ret_0> caster; - return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::getOriginalReceivedTimeStamp(); + return CObservationReflectivity::exportTxtSupported(); } - std::string asString() const override { + std::string exportTxtHeader() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -745,37 +737,38 @@ struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs:: } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::asString(); + return CObservationReflectivity::exportTxtHeader(); } - bool exportTxtSupported() const override { + std::string exportTxtDataRow() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::exportTxtSupported(); + return CObservationReflectivity::exportTxtDataRow(); } - std::string exportTxtHeader() const override { + using _binder_ret_0 = mrpt::Clock::time_point; + _binder_ret_0 getOriginalReceivedTimeStamp() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); if (overload) { auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); + if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { + static pybind11::detail::override_caster_t<_binder_ret_0> caster; + return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); } - else return pybind11::detail::cast_safe(std::move(o)); + else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); } - return CObservation::exportTxtHeader(); + return CObservation::getOriginalReceivedTimeStamp(); } - std::string exportTxtDataRow() const override { + std::string asString() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -784,11 +777,11 @@ struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs:: } else return pybind11::detail::cast_safe(std::move(o)); } - return CObservation::exportTxtDataRow(); + return CObservation::asString(); } void unload() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -801,7 +794,7 @@ struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs:: } void load_impl() const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -814,8 +807,58 @@ struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs:: } }; -void bind_mrpt_obs_CObservationOdometry(std::function< pybind11::module &(std::string const &namespace_) > &M) +void bind_mrpt_obs_CObservationBearingRange(std::function< pybind11::module &(std::string const &namespace_) > &M) { + { // mrpt::obs::CObservationBearingRange file:mrpt/obs/CObservationBearingRange.h line:28 + pybind11::class_, PyCallBack_mrpt_obs_CObservationBearingRange, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationBearingRange", "This observation represents a number of range-bearing value pairs, each one\n for a detected landmark, which optionally can have identification IDs.\n This class can manage sensors that detect landmarks in a 2D plane (e.g. a\n laser scanner) or in the 3D space (e.g. a camera). There are\n two direction angles: yaw (azimuth) and pitch (negative elevation). For 2D\n sensors, the pitch must be always set to 0.\n See CObservationBearingRange::validCovariances for the instructions to fill\n the uncertainty covariances.\n \n\n CObservation\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationBearingRange(); }, [](){ return new PyCallBack_mrpt_obs_CObservationBearingRange(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservationBearingRange const &o){ return new PyCallBack_mrpt_obs_CObservationBearingRange(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::CObservationBearingRange const &o){ return new mrpt::obs::CObservationBearingRange(o); } ) ); + cl.def_readwrite("minSensorDistance", &mrpt::obs::CObservationBearingRange::minSensorDistance); + cl.def_readwrite("maxSensorDistance", &mrpt::obs::CObservationBearingRange::maxSensorDistance); + cl.def_readwrite("fieldOfView_yaw", &mrpt::obs::CObservationBearingRange::fieldOfView_yaw); + cl.def_readwrite("fieldOfView_pitch", &mrpt::obs::CObservationBearingRange::fieldOfView_pitch); + cl.def_readwrite("sensorLocationOnRobot", &mrpt::obs::CObservationBearingRange::sensorLocationOnRobot); + cl.def_readwrite("sensedData", &mrpt::obs::CObservationBearingRange::sensedData); + cl.def_readwrite("validCovariances", &mrpt::obs::CObservationBearingRange::validCovariances); + cl.def_readwrite("sensor_std_range", &mrpt::obs::CObservationBearingRange::sensor_std_range); + cl.def_readwrite("sensor_std_yaw", &mrpt::obs::CObservationBearingRange::sensor_std_yaw); + cl.def_readwrite("sensor_std_pitch", &mrpt::obs::CObservationBearingRange::sensor_std_pitch); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservationBearingRange::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservationBearingRange::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservationBearingRange::*)() const) &mrpt::obs::CObservationBearingRange::GetRuntimeClass, "C++: mrpt::obs::CObservationBearingRange::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservationBearingRange::*)() const) &mrpt::obs::CObservationBearingRange::clone, "C++: mrpt::obs::CObservationBearingRange::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservationBearingRange::CreateObject, "C++: mrpt::obs::CObservationBearingRange::CreateObject() --> class std::shared_ptr"); + cl.def("debugPrintOut", (void (mrpt::obs::CObservationBearingRange::*)()) &mrpt::obs::CObservationBearingRange::debugPrintOut, "Prints out the contents of the object.\n\nC++: mrpt::obs::CObservationBearingRange::debugPrintOut() --> void"); + cl.def("getSensorPose", (void (mrpt::obs::CObservationBearingRange::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationBearingRange::getSensorPose, "C++: mrpt::obs::CObservationBearingRange::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); + cl.def("setSensorPose", (void (mrpt::obs::CObservationBearingRange::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationBearingRange::setSensorPose, "C++: mrpt::obs::CObservationBearingRange::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); + cl.def("assign", (class mrpt::obs::CObservationBearingRange & (mrpt::obs::CObservationBearingRange::*)(const class mrpt::obs::CObservationBearingRange &)) &mrpt::obs::CObservationBearingRange::operator=, "C++: mrpt::obs::CObservationBearingRange::operator=(const class mrpt::obs::CObservationBearingRange &) --> class mrpt::obs::CObservationBearingRange &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::CObservationBearingRange::TMeasurement file:mrpt/obs/CObservationBearingRange.h line:51 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TMeasurement", "Each one of the measurements:"); + cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationBearingRange::TMeasurement(); } ) ); + cl.def_readwrite("range", &mrpt::obs::CObservationBearingRange::TMeasurement::range); + cl.def_readwrite("yaw", &mrpt::obs::CObservationBearingRange::TMeasurement::yaw); + cl.def_readwrite("pitch", &mrpt::obs::CObservationBearingRange::TMeasurement::pitch); + cl.def_readwrite("landmarkID", &mrpt::obs::CObservationBearingRange::TMeasurement::landmarkID); + cl.def_readwrite("covariance", &mrpt::obs::CObservationBearingRange::TMeasurement::covariance); + } + + } + { // mrpt::obs::CObservationComment file:mrpt/obs/CObservationComment.h line:24 + pybind11::class_, PyCallBack_mrpt_obs_CObservationComment, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationComment", "This \"observation\" is actually a placeholder for a text block with comments\n or additional parameters attached to a given rawlog file.\n There should be only one of this observations in a rawlog file, and it's\n recommended to insert/modify them from the application RawlogViewer.\n\n \n CObservation\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationComment(); }, [](){ return new PyCallBack_mrpt_obs_CObservationComment(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservationComment const &o){ return new PyCallBack_mrpt_obs_CObservationComment(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::CObservationComment const &o){ return new mrpt::obs::CObservationComment(o); } ) ); + cl.def_readwrite("text", &mrpt::obs::CObservationComment::text); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservationComment::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservationComment::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservationComment::*)() const) &mrpt::obs::CObservationComment::GetRuntimeClass, "C++: mrpt::obs::CObservationComment::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservationComment::*)() const) &mrpt::obs::CObservationComment::clone, "C++: mrpt::obs::CObservationComment::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservationComment::CreateObject, "C++: mrpt::obs::CObservationComment::CreateObject() --> class std::shared_ptr"); + cl.def("getSensorPose", (void (mrpt::obs::CObservationComment::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationComment::getSensorPose, "C++: mrpt::obs::CObservationComment::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("")); + cl.def("setSensorPose", (void (mrpt::obs::CObservationComment::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationComment::setSensorPose, "C++: mrpt::obs::CObservationComment::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("")); + cl.def("assign", (class mrpt::obs::CObservationComment & (mrpt::obs::CObservationComment::*)(const class mrpt::obs::CObservationComment &)) &mrpt::obs::CObservationComment::operator=, "C++: mrpt::obs::CObservationComment::operator=(const class mrpt::obs::CObservationComment &) --> class mrpt::obs::CObservationComment &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } { // mrpt::obs::CObservationOdometry file:mrpt/obs/CObservationOdometry.h line:32 pybind11::class_, PyCallBack_mrpt_obs_CObservationOdometry, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationOdometry", "An observation of the current (cumulative) odometry for a wheeled robot.\n This provides the relative pose of the robot with respect to the `odom`\n frame of reference, in \"ROS parlance\".\n\n This kind of observation more naturally fits the \"observation-only\" rawlog\n format, since odometry increments are normally used in \"sensory-frame based\"\n datasets. However, the user is free to use them whenever it is useful. Refer\n to the [rawlog format description](rawlog_format.html).\n\n \n CObservation, CActionRobotMovement2D\n \n\n\n "); cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationOdometry(); }, [](){ return new PyCallBack_mrpt_obs_CObservationOdometry(); } ) ); @@ -854,51 +897,4 @@ void bind_mrpt_obs_CObservationOdometry(std::function< pybind11::module &(std::s cl.def("exportTxtDataRow", (std::string (mrpt::obs::CObservationReflectivity::*)() const) &mrpt::obs::CObservationReflectivity::exportTxtDataRow, "C++: mrpt::obs::CObservationReflectivity::exportTxtDataRow() const --> std::string"); cl.def("assign", (class mrpt::obs::CObservationReflectivity & (mrpt::obs::CObservationReflectivity::*)(const class mrpt::obs::CObservationReflectivity &)) &mrpt::obs::CObservationReflectivity::operator=, "C++: mrpt::obs::CObservationReflectivity::operator=(const class mrpt::obs::CObservationReflectivity &) --> class mrpt::obs::CObservationReflectivity &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::obs::CObservationRobotPose file:mrpt/obs/CObservationRobotPose.h line:21 - pybind11::class_, PyCallBack_mrpt_obs_CObservationRobotPose, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationRobotPose", "An observation providing an alternative robot pose from an external source.\n \n\n CObservation\n \n\n\n "); - cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationRobotPose(); }, [](){ return new PyCallBack_mrpt_obs_CObservationRobotPose(); } ) ); - cl.def_readwrite("pose", &mrpt::obs::CObservationRobotPose::pose); - cl.def_readwrite("sensorPose", &mrpt::obs::CObservationRobotPose::sensorPose); - cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservationRobotPose::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservationRobotPose::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); - cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::GetRuntimeClass, "C++: mrpt::obs::CObservationRobotPose::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); - cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::clone, "C++: mrpt::obs::CObservationRobotPose::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); - cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservationRobotPose::CreateObject, "C++: mrpt::obs::CObservationRobotPose::CreateObject() --> class std::shared_ptr"); - cl.def("getSensorPose", (void (mrpt::obs::CObservationRobotPose::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationRobotPose::getSensorPose, "C++: mrpt::obs::CObservationRobotPose::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); - cl.def("setSensorPose", (void (mrpt::obs::CObservationRobotPose::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationRobotPose::setSensorPose, "C++: mrpt::obs::CObservationRobotPose::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); - cl.def("exportTxtSupported", (bool (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::exportTxtSupported, "C++: mrpt::obs::CObservationRobotPose::exportTxtSupported() const --> bool"); - cl.def("exportTxtHeader", (std::string (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::exportTxtHeader, "C++: mrpt::obs::CObservationRobotPose::exportTxtHeader() const --> std::string"); - cl.def("exportTxtDataRow", (std::string (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::exportTxtDataRow, "C++: mrpt::obs::CObservationRobotPose::exportTxtDataRow() const --> std::string"); - cl.def("assign", (class mrpt::obs::CObservationRobotPose & (mrpt::obs::CObservationRobotPose::*)(const class mrpt::obs::CObservationRobotPose &)) &mrpt::obs::CObservationRobotPose::operator=, "C++: mrpt::obs::CObservationRobotPose::operator=(const class mrpt::obs::CObservationRobotPose &) --> class mrpt::obs::CObservationRobotPose &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - { // mrpt::obs::TStereoImageFeatures file:mrpt/obs/CObservationStereoImagesFeatures.h line:21 - pybind11::class_> cl(M("mrpt::obs"), "TStereoImageFeatures", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::TStereoImageFeatures(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::TStereoImageFeatures const &o){ return new mrpt::obs::TStereoImageFeatures(o); } ) ); - cl.def_readwrite("pixels", &mrpt::obs::TStereoImageFeatures::pixels); - cl.def_readwrite("ID", &mrpt::obs::TStereoImageFeatures::ID); - cl.def("assign", (struct mrpt::obs::TStereoImageFeatures & (mrpt::obs::TStereoImageFeatures::*)(const struct mrpt::obs::TStereoImageFeatures &)) &mrpt::obs::TStereoImageFeatures::operator=, "C++: mrpt::obs::TStereoImageFeatures::operator=(const struct mrpt::obs::TStereoImageFeatures &) --> struct mrpt::obs::TStereoImageFeatures &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - { // mrpt::obs::CObservationStereoImagesFeatures file:mrpt/obs/CObservationStereoImagesFeatures.h line:36 - pybind11::class_, PyCallBack_mrpt_obs_CObservationStereoImagesFeatures, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationStereoImagesFeatures", "Declares a class derived from \"CObservation\" that encapsules a pair of\n cameras and a set of matched image features extracted from them.\n\n NOTE: The image features stored in this class are NOT supposed to be\n UNDISTORTED, but the TCamera members must provide their distortion params.\n A zero-vector of distortion params means a set of UNDISTORTED pixels.\n \n\n CObservation\n \n\n\n "); - cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationStereoImagesFeatures(); }, [](){ return new PyCallBack_mrpt_obs_CObservationStereoImagesFeatures(); } ) ); - cl.def( pybind11::init(), pybind11::arg("cLeft"), pybind11::arg("cRight"), pybind11::arg("rCPose"), pybind11::arg("cPORobot") ); - - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservationStereoImagesFeatures const &o){ return new PyCallBack_mrpt_obs_CObservationStereoImagesFeatures(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::CObservationStereoImagesFeatures const &o){ return new mrpt::obs::CObservationStereoImagesFeatures(o); } ) ); - cl.def_readwrite("cameraLeft", &mrpt::obs::CObservationStereoImagesFeatures::cameraLeft); - cl.def_readwrite("cameraRight", &mrpt::obs::CObservationStereoImagesFeatures::cameraRight); - cl.def_readwrite("rightCameraPose", &mrpt::obs::CObservationStereoImagesFeatures::rightCameraPose); - cl.def_readwrite("cameraPoseOnRobot", &mrpt::obs::CObservationStereoImagesFeatures::cameraPoseOnRobot); - cl.def_readwrite("theFeatures", &mrpt::obs::CObservationStereoImagesFeatures::theFeatures); - cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservationStereoImagesFeatures::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservationStereoImagesFeatures::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); - cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservationStereoImagesFeatures::*)() const) &mrpt::obs::CObservationStereoImagesFeatures::GetRuntimeClass, "C++: mrpt::obs::CObservationStereoImagesFeatures::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); - cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservationStereoImagesFeatures::*)() const) &mrpt::obs::CObservationStereoImagesFeatures::clone, "C++: mrpt::obs::CObservationStereoImagesFeatures::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); - cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservationStereoImagesFeatures::CreateObject, "C++: mrpt::obs::CObservationStereoImagesFeatures::CreateObject() --> class std::shared_ptr"); - cl.def("saveFeaturesToTextFile", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(const std::string &)) &mrpt::obs::CObservationStereoImagesFeatures::saveFeaturesToTextFile, "A method for storing the set of observed features in a text file in the\n format: \n ID ul vl ur vr \n being (ul,vl) and (ur,vr) the \"x\" and \"y\" coordinates for the left and\n right feature, respectively.\n\nC++: mrpt::obs::CObservationStereoImagesFeatures::saveFeaturesToTextFile(const std::string &) --> void", pybind11::arg("filename")); - cl.def("getSensorPose", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationStereoImagesFeatures::getSensorPose, "C++: mrpt::obs::CObservationStereoImagesFeatures::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); - cl.def("getSensorPose", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(class mrpt::poses::CPose3DQuat &) const) &mrpt::obs::CObservationStereoImagesFeatures::getSensorPose, "C++: mrpt::obs::CObservationStereoImagesFeatures::getSensorPose(class mrpt::poses::CPose3DQuat &) const --> void", pybind11::arg("out_sensorPose")); - cl.def("setSensorPose", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationStereoImagesFeatures::setSensorPose, "A general method to change the sensor pose on the robot in a\n mrpt::poses::CPose3D form.\n Note that most sensors will use the full (6D) CPose3DQuat, but see the\n derived classes for more details or special cases.\n \n\n getSensorPose\n\nC++: mrpt::obs::CObservationStereoImagesFeatures::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); - cl.def("setSensorPose", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(const class mrpt::poses::CPose3DQuat &)) &mrpt::obs::CObservationStereoImagesFeatures::setSensorPose, "A general method to change the sensor pose on the robot in a CPose3DQuat\n form.\n Note that most sensors will use the full (6D) CPose3DQuat, but see the\n derived classes for more details or special cases.\n \n\n getSensorPose\n\nC++: mrpt::obs::CObservationStereoImagesFeatures::setSensorPose(const class mrpt::poses::CPose3DQuat &) --> void", pybind11::arg("newSensorPose")); - cl.def("assign", (class mrpt::obs::CObservationStereoImagesFeatures & (mrpt::obs::CObservationStereoImagesFeatures::*)(const class mrpt::obs::CObservationStereoImagesFeatures &)) &mrpt::obs::CObservationStereoImagesFeatures::operator=, "C++: mrpt::obs::CObservationStereoImagesFeatures::operator=(const class mrpt::obs::CObservationStereoImagesFeatures &) --> class mrpt::obs::CObservationStereoImagesFeatures &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } } diff --git a/python/src/mrpt/obs/CObservationGPS.cpp b/python/src/mrpt/obs/CObservationGPS.cpp index cc903dc838..36b063489e 100644 --- a/python/src/mrpt/obs/CObservationGPS.cpp +++ b/python/src/mrpt/obs/CObservationGPS.cpp @@ -242,14 +242,16 @@ 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_, 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().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_, 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 (*)()) &mrpt::obs::CObservationGPS::Create, "C++: mrpt::obs::CObservationGPS::Create() --> class std::shared_ptr"); 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); @@ -257,7 +259,6 @@ void bind_mrpt_obs_CObservationGPS(std::function< pybind11::module &(std::string 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"); diff --git a/python/src/mrpt/obs/CObservationRobotPose.cpp b/python/src/mrpt/obs/CObservationRobotPose.cpp new file mode 100644 index 0000000000..add74adc32 --- /dev/null +++ b/python/src/mrpt/obs/CObservationRobotPose.cpp @@ -0,0 +1,629 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::obs::CObservationRobotPose file:mrpt/obs/CObservationRobotPose.h line:21 +struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservationRobotPose { + using mrpt::obs::CObservationRobotPose::CObservationRobotPose; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::serializeFrom(a0, a1); + } + void getSensorPose(class mrpt::poses::CPose3D & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::getSensorPose(a0); + } + void setSensorPose(const class mrpt::poses::CPose3D & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::setSensorPose(a0); + } + bool exportTxtSupported() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::exportTxtSupported(); + } + std::string exportTxtHeader() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::exportTxtHeader(); + } + std::string exportTxtDataRow() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::exportTxtDataRow(); + } + using _binder_ret_0 = mrpt::Clock::time_point; + _binder_ret_0 getOriginalReceivedTimeStamp() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { + static pybind11::detail::override_caster_t<_binder_ret_0> caster; + return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); + } + else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); + } + return CObservation::getOriginalReceivedTimeStamp(); + } + std::string asString() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::asString(); + } + void unload() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::unload(); + } + void load_impl() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::load_impl(); + } +}; + +// mrpt::obs::CObservationStereoImagesFeatures file:mrpt/obs/CObservationStereoImagesFeatures.h line:36 +struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs::CObservationStereoImagesFeatures { + using mrpt::obs::CObservationStereoImagesFeatures::CObservationStereoImagesFeatures; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::serializeFrom(a0, a1); + } + void getSensorPose(class mrpt::poses::CPose3D & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::getSensorPose(a0); + } + void setSensorPose(const class mrpt::poses::CPose3D & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::setSensorPose(a0); + } + using _binder_ret_0 = mrpt::Clock::time_point; + _binder_ret_0 getOriginalReceivedTimeStamp() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { + static pybind11::detail::override_caster_t<_binder_ret_0> caster; + return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); + } + else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); + } + return CObservation::getOriginalReceivedTimeStamp(); + } + std::string asString() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::asString(); + } + bool exportTxtSupported() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::exportTxtSupported(); + } + std::string exportTxtHeader() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::exportTxtHeader(); + } + std::string exportTxtDataRow() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::exportTxtDataRow(); + } + void unload() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::unload(); + } + void load_impl() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "load_impl"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::load_impl(); + } +}; + +// mrpt::obs::CRawlog file:mrpt/obs/CRawlog.h line:62 +struct PyCallBack_mrpt_obs_CRawlog : public mrpt::obs::CRawlog { + using mrpt::obs::CRawlog::CRawlog; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRawlog::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRawlog::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRawlog::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRawlog::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRawlog::serializeFrom(a0, a1); + } +}; + +void bind_mrpt_obs_CObservationRobotPose(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::obs::CObservationRobotPose file:mrpt/obs/CObservationRobotPose.h line:21 + pybind11::class_, PyCallBack_mrpt_obs_CObservationRobotPose, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationRobotPose", "An observation providing an alternative robot pose from an external source.\n \n\n CObservation\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationRobotPose(); }, [](){ return new PyCallBack_mrpt_obs_CObservationRobotPose(); } ) ); + cl.def_readwrite("pose", &mrpt::obs::CObservationRobotPose::pose); + cl.def_readwrite("sensorPose", &mrpt::obs::CObservationRobotPose::sensorPose); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservationRobotPose::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservationRobotPose::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::GetRuntimeClass, "C++: mrpt::obs::CObservationRobotPose::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::clone, "C++: mrpt::obs::CObservationRobotPose::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservationRobotPose::CreateObject, "C++: mrpt::obs::CObservationRobotPose::CreateObject() --> class std::shared_ptr"); + cl.def("getSensorPose", (void (mrpt::obs::CObservationRobotPose::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationRobotPose::getSensorPose, "C++: mrpt::obs::CObservationRobotPose::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); + cl.def("setSensorPose", (void (mrpt::obs::CObservationRobotPose::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationRobotPose::setSensorPose, "C++: mrpt::obs::CObservationRobotPose::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); + cl.def("exportTxtSupported", (bool (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::exportTxtSupported, "C++: mrpt::obs::CObservationRobotPose::exportTxtSupported() const --> bool"); + cl.def("exportTxtHeader", (std::string (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::exportTxtHeader, "C++: mrpt::obs::CObservationRobotPose::exportTxtHeader() const --> std::string"); + cl.def("exportTxtDataRow", (std::string (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::exportTxtDataRow, "C++: mrpt::obs::CObservationRobotPose::exportTxtDataRow() const --> std::string"); + cl.def("assign", (class mrpt::obs::CObservationRobotPose & (mrpt::obs::CObservationRobotPose::*)(const class mrpt::obs::CObservationRobotPose &)) &mrpt::obs::CObservationRobotPose::operator=, "C++: mrpt::obs::CObservationRobotPose::operator=(const class mrpt::obs::CObservationRobotPose &) --> class mrpt::obs::CObservationRobotPose &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::obs::TStereoImageFeatures file:mrpt/obs/CObservationStereoImagesFeatures.h line:21 + pybind11::class_> cl(M("mrpt::obs"), "TStereoImageFeatures", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::TStereoImageFeatures(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::TStereoImageFeatures const &o){ return new mrpt::obs::TStereoImageFeatures(o); } ) ); + cl.def_readwrite("pixels", &mrpt::obs::TStereoImageFeatures::pixels); + cl.def_readwrite("ID", &mrpt::obs::TStereoImageFeatures::ID); + cl.def("assign", (struct mrpt::obs::TStereoImageFeatures & (mrpt::obs::TStereoImageFeatures::*)(const struct mrpt::obs::TStereoImageFeatures &)) &mrpt::obs::TStereoImageFeatures::operator=, "C++: mrpt::obs::TStereoImageFeatures::operator=(const struct mrpt::obs::TStereoImageFeatures &) --> struct mrpt::obs::TStereoImageFeatures &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::obs::CObservationStereoImagesFeatures file:mrpt/obs/CObservationStereoImagesFeatures.h line:36 + pybind11::class_, PyCallBack_mrpt_obs_CObservationStereoImagesFeatures, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationStereoImagesFeatures", "Declares a class derived from \"CObservation\" that encapsules a pair of\n cameras and a set of matched image features extracted from them.\n\n NOTE: The image features stored in this class are NOT supposed to be\n UNDISTORTED, but the TCamera members must provide their distortion params.\n A zero-vector of distortion params means a set of UNDISTORTED pixels.\n \n\n CObservation\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationStereoImagesFeatures(); }, [](){ return new PyCallBack_mrpt_obs_CObservationStereoImagesFeatures(); } ) ); + cl.def( pybind11::init(), pybind11::arg("cLeft"), pybind11::arg("cRight"), pybind11::arg("rCPose"), pybind11::arg("cPORobot") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservationStereoImagesFeatures const &o){ return new PyCallBack_mrpt_obs_CObservationStereoImagesFeatures(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::CObservationStereoImagesFeatures const &o){ return new mrpt::obs::CObservationStereoImagesFeatures(o); } ) ); + cl.def_readwrite("cameraLeft", &mrpt::obs::CObservationStereoImagesFeatures::cameraLeft); + cl.def_readwrite("cameraRight", &mrpt::obs::CObservationStereoImagesFeatures::cameraRight); + cl.def_readwrite("rightCameraPose", &mrpt::obs::CObservationStereoImagesFeatures::rightCameraPose); + cl.def_readwrite("cameraPoseOnRobot", &mrpt::obs::CObservationStereoImagesFeatures::cameraPoseOnRobot); + cl.def_readwrite("theFeatures", &mrpt::obs::CObservationStereoImagesFeatures::theFeatures); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservationStereoImagesFeatures::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservationStereoImagesFeatures::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservationStereoImagesFeatures::*)() const) &mrpt::obs::CObservationStereoImagesFeatures::GetRuntimeClass, "C++: mrpt::obs::CObservationStereoImagesFeatures::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservationStereoImagesFeatures::*)() const) &mrpt::obs::CObservationStereoImagesFeatures::clone, "C++: mrpt::obs::CObservationStereoImagesFeatures::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservationStereoImagesFeatures::CreateObject, "C++: mrpt::obs::CObservationStereoImagesFeatures::CreateObject() --> class std::shared_ptr"); + cl.def("saveFeaturesToTextFile", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(const std::string &)) &mrpt::obs::CObservationStereoImagesFeatures::saveFeaturesToTextFile, "A method for storing the set of observed features in a text file in the\n format: \n ID ul vl ur vr \n being (ul,vl) and (ur,vr) the \"x\" and \"y\" coordinates for the left and\n right feature, respectively.\n\nC++: mrpt::obs::CObservationStereoImagesFeatures::saveFeaturesToTextFile(const std::string &) --> void", pybind11::arg("filename")); + cl.def("getSensorPose", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationStereoImagesFeatures::getSensorPose, "C++: mrpt::obs::CObservationStereoImagesFeatures::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); + cl.def("getSensorPose", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(class mrpt::poses::CPose3DQuat &) const) &mrpt::obs::CObservationStereoImagesFeatures::getSensorPose, "C++: mrpt::obs::CObservationStereoImagesFeatures::getSensorPose(class mrpt::poses::CPose3DQuat &) const --> void", pybind11::arg("out_sensorPose")); + cl.def("setSensorPose", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationStereoImagesFeatures::setSensorPose, "A general method to change the sensor pose on the robot in a\n mrpt::poses::CPose3D form.\n Note that most sensors will use the full (6D) CPose3DQuat, but see the\n derived classes for more details or special cases.\n \n\n getSensorPose\n\nC++: mrpt::obs::CObservationStereoImagesFeatures::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); + cl.def("setSensorPose", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(const class mrpt::poses::CPose3DQuat &)) &mrpt::obs::CObservationStereoImagesFeatures::setSensorPose, "A general method to change the sensor pose on the robot in a CPose3DQuat\n form.\n Note that most sensors will use the full (6D) CPose3DQuat, but see the\n derived classes for more details or special cases.\n \n\n getSensorPose\n\nC++: mrpt::obs::CObservationStereoImagesFeatures::setSensorPose(const class mrpt::poses::CPose3DQuat &) --> void", pybind11::arg("newSensorPose")); + cl.def("assign", (class mrpt::obs::CObservationStereoImagesFeatures & (mrpt::obs::CObservationStereoImagesFeatures::*)(const class mrpt::obs::CObservationStereoImagesFeatures &)) &mrpt::obs::CObservationStereoImagesFeatures::operator=, "C++: mrpt::obs::CObservationStereoImagesFeatures::operator=(const class mrpt::obs::CObservationStereoImagesFeatures &) --> class mrpt::obs::CObservationStereoImagesFeatures &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::obs::CRawlog file:mrpt/obs/CRawlog.h line:62 + pybind11::class_, PyCallBack_mrpt_obs_CRawlog, mrpt::serialization::CSerializable> cl(M("mrpt::obs"), "CRawlog", "The main class for loading and processing robotics datasets, or \"rawlogs\".\n\n Please, refer to the [rawlog format specification](rawlog_format.html).\n\n In short, this class stores a sequence of objects, in one of two possible\nformats:\n - Format #1: A sequence of actions and observations. There is a sequence\nof objects, where each one can be of one type:\n - An action: Implemented as a CActionCollection object, the\nactuation\nof the robot (i.e. odometry increment).\n - Observations: Implemented as a CSensoryFrame, refering to a set of\nrobot observations from the same pose.\n - Format #2: A sequence of actions and observations. There is a sequence\nof objects, where each one can be of one type:\n\n See also [RawLogViewer](app_RawLogViewer.html) for a GUI application for\n quick inspection and analysis of rawlogs.\n\n There is a field for dataset plain-text comments (human-friendly description,\n blocks of parameters, etc.) accessible through CRawlog::getCommentText() and\n CRawlog::setCommentText().\n\n This container provides a STL container-like interface (see CRawlog::begin,\n CRawlog::iterator, ...).\n\n \n There is a static helper method CRawlog::detectImagesDirectory() to\n identify the directory where external images are stored.\n\n \n CSensoryFrame,\n [Dataset file format](robotics_file_formats.html#datasets).\n\n \n\n "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CRawlog(); }, [](){ return new PyCallBack_mrpt_obs_CRawlog(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CRawlog const &o){ return new PyCallBack_mrpt_obs_CRawlog(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::CRawlog const &o){ return new mrpt::obs::CRawlog(o); } ) ); + + pybind11::enum_(cl, "TEntryType", pybind11::arithmetic(), "The type of each entry in a rawlog.\n \n\n CRawlog::getType") + .value("etSensoryFrame", mrpt::obs::CRawlog::etSensoryFrame) + .value("etActionCollection", mrpt::obs::CRawlog::etActionCollection) + .value("etObservation", mrpt::obs::CRawlog::etObservation) + .value("etOther", mrpt::obs::CRawlog::etOther) + .export_values(); + + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CRawlog::GetRuntimeClassIdStatic, "C++: mrpt::obs::CRawlog::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::GetRuntimeClass, "C++: mrpt::obs::CRawlog::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::clone, "C++: mrpt::obs::CRawlog::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CRawlog::CreateObject, "C++: mrpt::obs::CRawlog::CreateObject() --> class std::shared_ptr"); + cl.def("getCommentText", (void (mrpt::obs::CRawlog::*)(std::string &) const) &mrpt::obs::CRawlog::getCommentText, "Returns the block of comment text for the rawlog \n\nC++: mrpt::obs::CRawlog::getCommentText(std::string &) const --> void", pybind11::arg("t")); + cl.def("getCommentText", (std::string (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::getCommentText, "Returns the block of comment text for the rawlog \n\nC++: mrpt::obs::CRawlog::getCommentText() const --> std::string"); + cl.def("setCommentText", (void (mrpt::obs::CRawlog::*)(const std::string &)) &mrpt::obs::CRawlog::setCommentText, "Changes the block of comment text for the rawlog \n\nC++: mrpt::obs::CRawlog::setCommentText(const std::string &) --> void", pybind11::arg("t")); + cl.def("getCommentTextAsConfigFile", (void (mrpt::obs::CRawlog::*)(class mrpt::config::CConfigFileMemory &) const) &mrpt::obs::CRawlog::getCommentTextAsConfigFile, "Saves the block of comment text for the rawlog into the passed config\n file object. \n\nC++: mrpt::obs::CRawlog::getCommentTextAsConfigFile(class mrpt::config::CConfigFileMemory &) const --> void", pybind11::arg("memCfg")); + cl.def("clear", (void (mrpt::obs::CRawlog::*)()) &mrpt::obs::CRawlog::clear, "Clear the sequence of actions/observations. Smart pointers to objects\n previously in the rawlog will remain being valid. \n\nC++: mrpt::obs::CRawlog::clear() --> void"); + cl.def("empty", (bool (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::empty, "Returns true if the rawlog is empty \n\nC++: mrpt::obs::CRawlog::empty() const --> bool"); + cl.def("insert", (void (mrpt::obs::CRawlog::*)(class mrpt::obs::CAction &)) &mrpt::obs::CRawlog::insert, "Add an action to the sequence: a collection of just one element is\n created.\n The object is duplicated, so the original one can be freed if desired.\n\nC++: mrpt::obs::CRawlog::insert(class mrpt::obs::CAction &) --> void", pybind11::arg("action")); + cl.def("insert", (void (mrpt::obs::CRawlog::*)(class mrpt::obs::CActionCollection &)) &mrpt::obs::CRawlog::insert, "Add a set of actions to the sequence; the object is duplicated, so the\n original one can be freed if desired.\n \n\n insert, insert\n\nC++: mrpt::obs::CRawlog::insert(class mrpt::obs::CActionCollection &) --> void", pybind11::arg("action")); + cl.def("insert", (void (mrpt::obs::CRawlog::*)(class mrpt::obs::CSensoryFrame &)) &mrpt::obs::CRawlog::insert, "Add a set of observations to the sequence; the object is duplicated, so\n the original one can be free if desired.\n\nC++: mrpt::obs::CRawlog::insert(class mrpt::obs::CSensoryFrame &) --> void", pybind11::arg("observations")); + cl.def("insert", (void (mrpt::obs::CRawlog::*)(const class std::shared_ptr &)) &mrpt::obs::CRawlog::insert, "Generic add for a smart pointer to a CSerializable object:\n\nC++: mrpt::obs::CRawlog::insert(const class std::shared_ptr &) --> void", pybind11::arg("obj")); + cl.def("loadFromRawLogFile", [](mrpt::obs::CRawlog &o, const std::string & a0) -> bool { return o.loadFromRawLogFile(a0); }, "", pybind11::arg("fileName")); + cl.def("loadFromRawLogFile", (bool (mrpt::obs::CRawlog::*)(const std::string &, bool)) &mrpt::obs::CRawlog::loadFromRawLogFile, "Load the contents from a file containing one of these possibilities:\n - A \"CRawlog\" object.\n - Directly the sequence of objects (pairs\n `CSensoryFrame`/`CActionCollection` or `CObservation*` objects). In this\n case the method stops reading on EOF of an unrecogniced class name.\n - Only if `non_obs_objects_are_legal` is true, any `CSerializable`\n object is allowed in the log file. Otherwise, the read stops on classes\n different from the ones listed in the item above.\n \n\n It returns false upon error reading or accessing the file.\n\nC++: mrpt::obs::CRawlog::loadFromRawLogFile(const std::string &, bool) --> bool", pybind11::arg("fileName"), pybind11::arg("non_obs_objects_are_legal")); + cl.def("saveToRawLogFile", (bool (mrpt::obs::CRawlog::*)(const std::string &) const) &mrpt::obs::CRawlog::saveToRawLogFile, "Saves the contents to a rawlog-file, compatible with RawlogViewer (As\n the sequence of internal objects).\n The file is saved with gz-commpressed if MRPT has gz-streams.\n \n\n It returns false if any error is found while writing/creating\n the target file.\n\nC++: mrpt::obs::CRawlog::saveToRawLogFile(const std::string &) const --> bool", pybind11::arg("fileName")); + cl.def("size", (size_t (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::size, "Returns the number of actions / observations object in the sequence. \n\nC++: mrpt::obs::CRawlog::size() const --> size_t"); + cl.def("getType", (enum mrpt::obs::CRawlog::TEntryType (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getType, "Returns the type of a given element.\n \n\n isAction, isObservation\n\nC++: mrpt::obs::CRawlog::getType(size_t) const --> enum mrpt::obs::CRawlog::TEntryType", pybind11::arg("index")); + cl.def("remove", (void (mrpt::obs::CRawlog::*)(size_t)) &mrpt::obs::CRawlog::remove, "Delete the action or observation stored in the given index.\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::remove(size_t) --> void", pybind11::arg("index")); + cl.def("remove", (void (mrpt::obs::CRawlog::*)(size_t, size_t)) &mrpt::obs::CRawlog::remove, "Delete the elements stored in the given range of indices (including both\n the first and last one).\n \n\n std::exception If any index is out of bounds\n\nC++: mrpt::obs::CRawlog::remove(size_t, size_t) --> void", pybind11::arg("first_index"), pybind11::arg("last_index")); + cl.def("getAsAction", (class std::shared_ptr (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getAsAction, "Returns the i'th element in the sequence, as being actions, where\n index=0 is the first object.\n If it is not a CActionCollection, it throws an exception. Do neighter\n modify nor delete the returned pointer.\n \n\n size, isAction, getAsObservations, getAsObservation\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::getAsAction(size_t) const --> class std::shared_ptr", pybind11::arg("index")); + cl.def("getAsObservations", (class std::shared_ptr (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getAsObservations, "Returns the i'th element in the sequence, as being an action, where\n index=0 is the first object.\n If it is not an CSensoryFrame, it throws an exception.\n \n\n size, isAction, getAsAction, getAsObservation\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::getAsObservations(size_t) const --> class std::shared_ptr", pybind11::arg("index")); + cl.def("getAsGeneric", (class std::shared_ptr (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getAsGeneric, "Returns the i'th element in the sequence, being its class whatever.\n \n\n size, isAction, getAsAction, getAsObservations\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::getAsGeneric(size_t) const --> class std::shared_ptr", pybind11::arg("index")); + cl.def("getAsObservation", (class std::shared_ptr (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getAsObservation, "Returns the i'th element in the sequence, as being an observation, where\n index=0 is the first object.\n If it is not an CObservation, it throws an exception. Do neighter\n modify nor delete the returned pointer.\n This is the proper method to obtain the objects stored in a \"only\n observations\"-rawlog file (named \"format #2\" above.\n \n\n size, isAction, getAsAction\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::getAsObservation(size_t) const --> class std::shared_ptr", pybind11::arg("index")); + cl.def("swap", (void (mrpt::obs::CRawlog::*)(class mrpt::obs::CRawlog &)) &mrpt::obs::CRawlog::swap, "Efficiently swap the contents of two existing objects.\n\nC++: mrpt::obs::CRawlog::swap(class mrpt::obs::CRawlog &) --> void", pybind11::arg("obj")); + cl.def_static("readActionObservationPair", (bool (*)(class mrpt::serialization::CArchive &, class std::shared_ptr &, class std::shared_ptr &, unsigned long &)) &mrpt::obs::CRawlog::readActionObservationPair, "Reads a consecutive pair action / observation from the rawlog opened at\n some input stream.\n Previous contents of action and observations are discarded, and\n upon exit they contain smart pointers to the new objects read from the\n rawlog file.\n The input/output variable \"rawlogEntry\" is just a counter of the last\n rawlog entry read, for logging or monitoring purposes.\n \n\n false if there was some error, true otherwise.\n \n\n getActionObservationPair, getActionObservationPairOrObservation\n\nC++: mrpt::obs::CRawlog::readActionObservationPair(class mrpt::serialization::CArchive &, class std::shared_ptr &, class std::shared_ptr &, unsigned long &) --> bool", pybind11::arg("inStream"), pybind11::arg("action"), pybind11::arg("observations"), pybind11::arg("rawlogEntry")); + cl.def_static("getActionObservationPairOrObservation", (bool (*)(class mrpt::serialization::CArchive &, class std::shared_ptr &, class std::shared_ptr &, class std::shared_ptr &, unsigned long &)) &mrpt::obs::CRawlog::getActionObservationPairOrObservation, "Reads a consecutive pair action/sensory_frame OR an observation,\n depending of the rawlog format, from the rawlog opened at some input\n stream.\n Previous contents of action and observations are discarded, and\n upon return they contain smart pointers to the new objects read from\n the rawlog file.\n\n Depending on the rawlog file format, at return either:\n - action/observations contain objects, or\n - observation contains an object.\n\n The input/output variable \"rawlogEntry\" is just a counter of the last\n rawlog entry read, for logging or monitoring purposes.\n \n\n false if there was some error, true otherwise.\n \n\n getActionObservationPair\n\nC++: mrpt::obs::CRawlog::getActionObservationPairOrObservation(class mrpt::serialization::CArchive &, class std::shared_ptr &, class std::shared_ptr &, class std::shared_ptr &, unsigned long &) --> bool", pybind11::arg("inStream"), pybind11::arg("action"), pybind11::arg("observations"), pybind11::arg("observation"), pybind11::arg("rawlogEntry")); + cl.def_static("ReadFromArchive", (class std::tuple, class std::shared_ptr, class std::shared_ptr > (*)(class mrpt::serialization::CArchive &, const unsigned long)) &mrpt::obs::CRawlog::ReadFromArchive, "Alternative to getActionObservationPairOrObservation() returning the\n tuple [readOk, rawlogEntryIndex, action,sf, obs], with either (action,sf)\n or (obs) as empty smart pointers depending on the rawlog file format.\n readOk is false on EOF or any other error.\n\nC++: mrpt::obs::CRawlog::ReadFromArchive(class mrpt::serialization::CArchive &, const unsigned long) --> class std::tuple, class std::shared_ptr, class std::shared_ptr >", pybind11::arg("inStream"), pybind11::arg("rawlogEntryIndex")); + cl.def("getActionObservationPair", (bool (mrpt::obs::CRawlog::*)(class std::shared_ptr &, class std::shared_ptr &, unsigned long &) const) &mrpt::obs::CRawlog::getActionObservationPair, "Gets the next consecutive pair action / observation from the rawlog\n loaded into this object.\n Previous contents of action and observations are discarded, and\n upon return they contain smart pointers to the next objects read from\n the rawlog dataset.\n The input/output variable \"rawlogEntry\" is just a counter of the last\n rawlog entry read, for logging or monitoring purposes.\n \n\n false if there was some error, true otherwise.\n \n\n readActionObservationPair\n\nC++: mrpt::obs::CRawlog::getActionObservationPair(class std::shared_ptr &, class std::shared_ptr &, unsigned long &) const --> bool", pybind11::arg("action"), pybind11::arg("observations"), pybind11::arg("rawlogEntry")); + cl.def_static("detectImagesDirectory", (std::string (*)(const std::string &)) &mrpt::obs::CRawlog::detectImagesDirectory, "Tries to auto-detect the external-images directory of the given rawlog\nfile.\n This searches for the existence of the directories:\n - \"/_Images\"\n - \"/_images\"\n - \"/_IMAGES\"\n - \"/Images\" (This one is returned if none of the\nchoices actually exists).\n\n The results from this function should be written into\nmrpt::img::CImage::getImagesPathBase() to enable automatic\n loading of extenrnally-stored images in rawlogs.\n\nC++: mrpt::obs::CRawlog::detectImagesDirectory(const std::string &) --> std::string", pybind11::arg("rawlogFilename")); + cl.def("assign", (class mrpt::obs::CRawlog & (mrpt::obs::CRawlog::*)(const class mrpt::obs::CRawlog &)) &mrpt::obs::CRawlog::operator=, "C++: mrpt::obs::CRawlog::operator=(const class mrpt::obs::CRawlog &) --> class mrpt::obs::CRawlog &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::CRawlog::iterator file:mrpt/obs/CRawlog.h line:232 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "iterator", "A normal iterator, plus the extra method \"getType\" to determine the\n type of each entry in the sequence. "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CRawlog::iterator(); } ) ); + cl.def("dereference", (class std::shared_ptr (mrpt::obs::CRawlog::iterator::*)()) &mrpt::obs::CRawlog::iterator::operator*, "C++: mrpt::obs::CRawlog::iterator::operator*() --> class std::shared_ptr"); + cl.def("getType", (enum mrpt::obs::CRawlog::TEntryType (mrpt::obs::CRawlog::iterator::*)() const) &mrpt::obs::CRawlog::iterator::getType, "C++: mrpt::obs::CRawlog::iterator::getType() const --> enum mrpt::obs::CRawlog::TEntryType"); + } + + { // mrpt::obs::CRawlog::const_iterator file:mrpt/obs/CRawlog.h line:288 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "const_iterator", "A normal iterator, plus the extra method \"getType\" to determine the type\n of each entry in the sequence. "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CRawlog::const_iterator(); } ) ); + cl.def("dereference", (const class std::shared_ptr (mrpt::obs::CRawlog::const_iterator::*)() const) &mrpt::obs::CRawlog::const_iterator::operator*, "C++: mrpt::obs::CRawlog::const_iterator::operator*() const --> const class std::shared_ptr"); + cl.def("getType", (enum mrpt::obs::CRawlog::TEntryType (mrpt::obs::CRawlog::const_iterator::*)() const) &mrpt::obs::CRawlog::const_iterator::getType, "C++: mrpt::obs::CRawlog::const_iterator::getType() const --> enum mrpt::obs::CRawlog::TEntryType"); + } + + } +} diff --git a/python/src/mrpt/obs/CRawlog.cpp b/python/src/mrpt/obs/CRawlog.cpp deleted file mode 100644 index 37eac426e3..0000000000 --- a/python/src/mrpt/obs/CRawlog.cpp +++ /dev/null @@ -1,176 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include // __str__ -#include -#include -#include -#include - -#include -#include -#include -#include - - -#ifndef BINDER_PYBIND11_TYPE_CASTER - #define BINDER_PYBIND11_TYPE_CASTER - PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) - PYBIND11_DECLARE_HOLDER_TYPE(T, T*) - PYBIND11_MAKE_OPAQUE(std::shared_ptr) -#endif - -// mrpt::obs::CRawlog file:mrpt/obs/CRawlog.h line:62 -struct PyCallBack_mrpt_obs_CRawlog : public mrpt::obs::CRawlog { - using mrpt::obs::CRawlog::CRawlog; - - const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CRawlog::GetRuntimeClass(); - } - class mrpt::rtti::CObject * clone() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CRawlog::clone(); - } - uint8_t serializeGetVersion() const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CRawlog::serializeGetVersion(); - } - void serializeTo(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CRawlog::serializeTo(a0); - } - void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); - if (overload) { - auto o = overload.operator()(a0, a1); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return CRawlog::serializeFrom(a0, a1); - } -}; - -void bind_mrpt_obs_CRawlog(std::function< pybind11::module &(std::string const &namespace_) > &M) -{ - { // mrpt::obs::CRawlog file:mrpt/obs/CRawlog.h line:62 - pybind11::class_, PyCallBack_mrpt_obs_CRawlog, mrpt::serialization::CSerializable> cl(M("mrpt::obs"), "CRawlog", "The main class for loading and processing robotics datasets, or \"rawlogs\".\n\n Please, refer to the [rawlog format specification](rawlog_format.html).\n\n In short, this class stores a sequence of objects, in one of two possible\nformats:\n - Format #1: A sequence of actions and observations. There is a sequence\nof objects, where each one can be of one type:\n - An action: Implemented as a CActionCollection object, the\nactuation\nof the robot (i.e. odometry increment).\n - Observations: Implemented as a CSensoryFrame, refering to a set of\nrobot observations from the same pose.\n - Format #2: A sequence of actions and observations. There is a sequence\nof objects, where each one can be of one type:\n\n See also [RawLogViewer](app_RawLogViewer.html) for a GUI application for\n quick inspection and analysis of rawlogs.\n\n There is a field for dataset plain-text comments (human-friendly description,\n blocks of parameters, etc.) accessible through CRawlog::getCommentText() and\n CRawlog::setCommentText().\n\n This container provides a STL container-like interface (see CRawlog::begin,\n CRawlog::iterator, ...).\n\n \n There is a static helper method CRawlog::detectImagesDirectory() to\n identify the directory where external images are stored.\n\n \n CSensoryFrame,\n [Dataset file format](robotics_file_formats.html#datasets).\n\n \n\n "); - cl.def( pybind11::init( [](){ return new mrpt::obs::CRawlog(); }, [](){ return new PyCallBack_mrpt_obs_CRawlog(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CRawlog const &o){ return new PyCallBack_mrpt_obs_CRawlog(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::CRawlog const &o){ return new mrpt::obs::CRawlog(o); } ) ); - - pybind11::enum_(cl, "TEntryType", pybind11::arithmetic(), "The type of each entry in a rawlog.\n \n\n CRawlog::getType") - .value("etSensoryFrame", mrpt::obs::CRawlog::etSensoryFrame) - .value("etActionCollection", mrpt::obs::CRawlog::etActionCollection) - .value("etObservation", mrpt::obs::CRawlog::etObservation) - .value("etOther", mrpt::obs::CRawlog::etOther) - .export_values(); - - cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CRawlog::GetRuntimeClassIdStatic, "C++: mrpt::obs::CRawlog::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); - cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::GetRuntimeClass, "C++: mrpt::obs::CRawlog::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); - cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::clone, "C++: mrpt::obs::CRawlog::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); - cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CRawlog::CreateObject, "C++: mrpt::obs::CRawlog::CreateObject() --> class std::shared_ptr"); - cl.def("getCommentText", (void (mrpt::obs::CRawlog::*)(std::string &) const) &mrpt::obs::CRawlog::getCommentText, "Returns the block of comment text for the rawlog \n\nC++: mrpt::obs::CRawlog::getCommentText(std::string &) const --> void", pybind11::arg("t")); - cl.def("getCommentText", (std::string (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::getCommentText, "Returns the block of comment text for the rawlog \n\nC++: mrpt::obs::CRawlog::getCommentText() const --> std::string"); - cl.def("setCommentText", (void (mrpt::obs::CRawlog::*)(const std::string &)) &mrpt::obs::CRawlog::setCommentText, "Changes the block of comment text for the rawlog \n\nC++: mrpt::obs::CRawlog::setCommentText(const std::string &) --> void", pybind11::arg("t")); - cl.def("getCommentTextAsConfigFile", (void (mrpt::obs::CRawlog::*)(class mrpt::config::CConfigFileMemory &) const) &mrpt::obs::CRawlog::getCommentTextAsConfigFile, "Saves the block of comment text for the rawlog into the passed config\n file object. \n\nC++: mrpt::obs::CRawlog::getCommentTextAsConfigFile(class mrpt::config::CConfigFileMemory &) const --> void", pybind11::arg("memCfg")); - cl.def("clear", (void (mrpt::obs::CRawlog::*)()) &mrpt::obs::CRawlog::clear, "Clear the sequence of actions/observations. Smart pointers to objects\n previously in the rawlog will remain being valid. \n\nC++: mrpt::obs::CRawlog::clear() --> void"); - cl.def("empty", (bool (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::empty, "Returns true if the rawlog is empty \n\nC++: mrpt::obs::CRawlog::empty() const --> bool"); - cl.def("insert", (void (mrpt::obs::CRawlog::*)(class mrpt::obs::CAction &)) &mrpt::obs::CRawlog::insert, "Add an action to the sequence: a collection of just one element is\n created.\n The object is duplicated, so the original one can be freed if desired.\n\nC++: mrpt::obs::CRawlog::insert(class mrpt::obs::CAction &) --> void", pybind11::arg("action")); - cl.def("insert", (void (mrpt::obs::CRawlog::*)(class mrpt::obs::CActionCollection &)) &mrpt::obs::CRawlog::insert, "Add a set of actions to the sequence; the object is duplicated, so the\n original one can be freed if desired.\n \n\n insert, insert\n\nC++: mrpt::obs::CRawlog::insert(class mrpt::obs::CActionCollection &) --> void", pybind11::arg("action")); - cl.def("insert", (void (mrpt::obs::CRawlog::*)(class mrpt::obs::CSensoryFrame &)) &mrpt::obs::CRawlog::insert, "Add a set of observations to the sequence; the object is duplicated, so\n the original one can be free if desired.\n\nC++: mrpt::obs::CRawlog::insert(class mrpt::obs::CSensoryFrame &) --> void", pybind11::arg("observations")); - cl.def("insert", (void (mrpt::obs::CRawlog::*)(const class std::shared_ptr &)) &mrpt::obs::CRawlog::insert, "Generic add for a smart pointer to a CSerializable object:\n\nC++: mrpt::obs::CRawlog::insert(const class std::shared_ptr &) --> void", pybind11::arg("obj")); - cl.def("loadFromRawLogFile", [](mrpt::obs::CRawlog &o, const std::string & a0) -> bool { return o.loadFromRawLogFile(a0); }, "", pybind11::arg("fileName")); - cl.def("loadFromRawLogFile", (bool (mrpt::obs::CRawlog::*)(const std::string &, bool)) &mrpt::obs::CRawlog::loadFromRawLogFile, "Load the contents from a file containing one of these possibilities:\n - A \"CRawlog\" object.\n - Directly the sequence of objects (pairs\n `CSensoryFrame`/`CActionCollection` or `CObservation*` objects). In this\n case the method stops reading on EOF of an unrecogniced class name.\n - Only if `non_obs_objects_are_legal` is true, any `CSerializable`\n object is allowed in the log file. Otherwise, the read stops on classes\n different from the ones listed in the item above.\n \n\n It returns false upon error reading or accessing the file.\n\nC++: mrpt::obs::CRawlog::loadFromRawLogFile(const std::string &, bool) --> bool", pybind11::arg("fileName"), pybind11::arg("non_obs_objects_are_legal")); - cl.def("saveToRawLogFile", (bool (mrpt::obs::CRawlog::*)(const std::string &) const) &mrpt::obs::CRawlog::saveToRawLogFile, "Saves the contents to a rawlog-file, compatible with RawlogViewer (As\n the sequence of internal objects).\n The file is saved with gz-commpressed if MRPT has gz-streams.\n \n\n It returns false if any error is found while writing/creating\n the target file.\n\nC++: mrpt::obs::CRawlog::saveToRawLogFile(const std::string &) const --> bool", pybind11::arg("fileName")); - cl.def("size", (size_t (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::size, "Returns the number of actions / observations object in the sequence. \n\nC++: mrpt::obs::CRawlog::size() const --> size_t"); - cl.def("getType", (enum mrpt::obs::CRawlog::TEntryType (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getType, "Returns the type of a given element.\n \n\n isAction, isObservation\n\nC++: mrpt::obs::CRawlog::getType(size_t) const --> enum mrpt::obs::CRawlog::TEntryType", pybind11::arg("index")); - cl.def("remove", (void (mrpt::obs::CRawlog::*)(size_t)) &mrpt::obs::CRawlog::remove, "Delete the action or observation stored in the given index.\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::remove(size_t) --> void", pybind11::arg("index")); - cl.def("remove", (void (mrpt::obs::CRawlog::*)(size_t, size_t)) &mrpt::obs::CRawlog::remove, "Delete the elements stored in the given range of indices (including both\n the first and last one).\n \n\n std::exception If any index is out of bounds\n\nC++: mrpt::obs::CRawlog::remove(size_t, size_t) --> void", pybind11::arg("first_index"), pybind11::arg("last_index")); - cl.def("getAsAction", (class std::shared_ptr (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getAsAction, "Returns the i'th element in the sequence, as being actions, where\n index=0 is the first object.\n If it is not a CActionCollection, it throws an exception. Do neighter\n modify nor delete the returned pointer.\n \n\n size, isAction, getAsObservations, getAsObservation\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::getAsAction(size_t) const --> class std::shared_ptr", pybind11::arg("index")); - cl.def("getAsObservations", (class std::shared_ptr (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getAsObservations, "Returns the i'th element in the sequence, as being an action, where\n index=0 is the first object.\n If it is not an CSensoryFrame, it throws an exception.\n \n\n size, isAction, getAsAction, getAsObservation\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::getAsObservations(size_t) const --> class std::shared_ptr", pybind11::arg("index")); - cl.def("getAsGeneric", (class std::shared_ptr (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getAsGeneric, "Returns the i'th element in the sequence, being its class whatever.\n \n\n size, isAction, getAsAction, getAsObservations\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::getAsGeneric(size_t) const --> class std::shared_ptr", pybind11::arg("index")); - cl.def("getAsObservation", (class std::shared_ptr (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getAsObservation, "Returns the i'th element in the sequence, as being an observation, where\n index=0 is the first object.\n If it is not an CObservation, it throws an exception. Do neighter\n modify nor delete the returned pointer.\n This is the proper method to obtain the objects stored in a \"only\n observations\"-rawlog file (named \"format #2\" above.\n \n\n size, isAction, getAsAction\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::getAsObservation(size_t) const --> class std::shared_ptr", pybind11::arg("index")); - cl.def("swap", (void (mrpt::obs::CRawlog::*)(class mrpt::obs::CRawlog &)) &mrpt::obs::CRawlog::swap, "Efficiently swap the contents of two existing objects.\n\nC++: mrpt::obs::CRawlog::swap(class mrpt::obs::CRawlog &) --> void", pybind11::arg("obj")); - cl.def_static("readActionObservationPair", (bool (*)(class mrpt::serialization::CArchive &, class std::shared_ptr &, class std::shared_ptr &, unsigned long &)) &mrpt::obs::CRawlog::readActionObservationPair, "Reads a consecutive pair action / observation from the rawlog opened at\n some input stream.\n Previous contents of action and observations are discarded, and\n upon exit they contain smart pointers to the new objects read from the\n rawlog file.\n The input/output variable \"rawlogEntry\" is just a counter of the last\n rawlog entry read, for logging or monitoring purposes.\n \n\n false if there was some error, true otherwise.\n \n\n getActionObservationPair, getActionObservationPairOrObservation\n\nC++: mrpt::obs::CRawlog::readActionObservationPair(class mrpt::serialization::CArchive &, class std::shared_ptr &, class std::shared_ptr &, unsigned long &) --> bool", pybind11::arg("inStream"), pybind11::arg("action"), pybind11::arg("observations"), pybind11::arg("rawlogEntry")); - cl.def_static("getActionObservationPairOrObservation", (bool (*)(class mrpt::serialization::CArchive &, class std::shared_ptr &, class std::shared_ptr &, class std::shared_ptr &, unsigned long &)) &mrpt::obs::CRawlog::getActionObservationPairOrObservation, "Reads a consecutive pair action/sensory_frame OR an observation,\n depending of the rawlog format, from the rawlog opened at some input\n stream.\n Previous contents of action and observations are discarded, and\n upon return they contain smart pointers to the new objects read from\n the rawlog file.\n\n Depending on the rawlog file format, at return either:\n - action/observations contain objects, or\n - observation contains an object.\n\n The input/output variable \"rawlogEntry\" is just a counter of the last\n rawlog entry read, for logging or monitoring purposes.\n \n\n false if there was some error, true otherwise.\n \n\n getActionObservationPair\n\nC++: mrpt::obs::CRawlog::getActionObservationPairOrObservation(class mrpt::serialization::CArchive &, class std::shared_ptr &, class std::shared_ptr &, class std::shared_ptr &, unsigned long &) --> bool", pybind11::arg("inStream"), pybind11::arg("action"), pybind11::arg("observations"), pybind11::arg("observation"), pybind11::arg("rawlogEntry")); - cl.def_static("ReadFromArchive", (class std::tuple, class std::shared_ptr, class std::shared_ptr > (*)(class mrpt::serialization::CArchive &, const unsigned long)) &mrpt::obs::CRawlog::ReadFromArchive, "Alternative to getActionObservationPairOrObservation() returning the\n tuple [readOk, rawlogEntryIndex, action,sf, obs], with either (action,sf)\n or (obs) as empty smart pointers depending on the rawlog file format.\n readOk is false on EOF or any other error.\n\nC++: mrpt::obs::CRawlog::ReadFromArchive(class mrpt::serialization::CArchive &, const unsigned long) --> class std::tuple, class std::shared_ptr, class std::shared_ptr >", pybind11::arg("inStream"), pybind11::arg("rawlogEntryIndex")); - cl.def("getActionObservationPair", (bool (mrpt::obs::CRawlog::*)(class std::shared_ptr &, class std::shared_ptr &, unsigned long &) const) &mrpt::obs::CRawlog::getActionObservationPair, "Gets the next consecutive pair action / observation from the rawlog\n loaded into this object.\n Previous contents of action and observations are discarded, and\n upon return they contain smart pointers to the next objects read from\n the rawlog dataset.\n The input/output variable \"rawlogEntry\" is just a counter of the last\n rawlog entry read, for logging or monitoring purposes.\n \n\n false if there was some error, true otherwise.\n \n\n readActionObservationPair\n\nC++: mrpt::obs::CRawlog::getActionObservationPair(class std::shared_ptr &, class std::shared_ptr &, unsigned long &) const --> bool", pybind11::arg("action"), pybind11::arg("observations"), pybind11::arg("rawlogEntry")); - cl.def_static("detectImagesDirectory", (std::string (*)(const std::string &)) &mrpt::obs::CRawlog::detectImagesDirectory, "Tries to auto-detect the external-images directory of the given rawlog\nfile.\n This searches for the existence of the directories:\n - \"/_Images\"\n - \"/_images\"\n - \"/_IMAGES\"\n - \"/Images\" (This one is returned if none of the\nchoices actually exists).\n\n The results from this function should be written into\nmrpt::img::CImage::getImagesPathBase() to enable automatic\n loading of extenrnally-stored images in rawlogs.\n\nC++: mrpt::obs::CRawlog::detectImagesDirectory(const std::string &) --> std::string", pybind11::arg("rawlogFilename")); - cl.def("assign", (class mrpt::obs::CRawlog & (mrpt::obs::CRawlog::*)(const class mrpt::obs::CRawlog &)) &mrpt::obs::CRawlog::operator=, "C++: mrpt::obs::CRawlog::operator=(const class mrpt::obs::CRawlog &) --> class mrpt::obs::CRawlog &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::CRawlog::iterator file:mrpt/obs/CRawlog.h line:232 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "iterator", "A normal iterator, plus the extra method \"getType\" to determine the\n type of each entry in the sequence. "); - cl.def( pybind11::init( [](){ return new mrpt::obs::CRawlog::iterator(); } ) ); - cl.def("dereference", (class std::shared_ptr (mrpt::obs::CRawlog::iterator::*)()) &mrpt::obs::CRawlog::iterator::operator*, "C++: mrpt::obs::CRawlog::iterator::operator*() --> class std::shared_ptr"); - cl.def("getType", (enum mrpt::obs::CRawlog::TEntryType (mrpt::obs::CRawlog::iterator::*)() const) &mrpt::obs::CRawlog::iterator::getType, "C++: mrpt::obs::CRawlog::iterator::getType() const --> enum mrpt::obs::CRawlog::TEntryType"); - } - - { // mrpt::obs::CRawlog::const_iterator file:mrpt/obs/CRawlog.h line:288 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "const_iterator", "A normal iterator, plus the extra method \"getType\" to determine the type\n of each entry in the sequence. "); - cl.def( pybind11::init( [](){ return new mrpt::obs::CRawlog::const_iterator(); } ) ); - cl.def("dereference", (const class std::shared_ptr (mrpt::obs::CRawlog::const_iterator::*)() const) &mrpt::obs::CRawlog::const_iterator::operator*, "C++: mrpt::obs::CRawlog::const_iterator::operator*() const --> const class std::shared_ptr"); - cl.def("getType", (enum mrpt::obs::CRawlog::TEntryType (mrpt::obs::CRawlog::const_iterator::*)() const) &mrpt::obs::CRawlog::const_iterator::getType, "C++: mrpt::obs::CRawlog::const_iterator::getType() const --> enum mrpt::obs::CRawlog::TEntryType"); - } - - } -} diff --git a/python/src/mrpt/obs/gnss_messages_type_list.cpp b/python/src/mrpt/obs/gnss_messages_type_list.cpp index 160d84b1a1..c6780ffb39 100644 --- a/python/src/mrpt/obs/gnss_messages_type_list.cpp +++ b/python/src/mrpt/obs/gnss_messages_type_list.cpp @@ -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(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(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(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(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(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(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(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(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(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(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(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(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_> 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(), 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_> 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_, 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_> 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_, 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_> 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("")); + } + + } } diff --git a/python/src/mrpt/typemeta/TEnumType.cpp b/python/src/mrpt/typemeta/TEnumType.cpp index 52d846e16b..d442dc94f4 100644 --- a/python/src/mrpt/typemeta/TEnumType.cpp +++ b/python/src/mrpt/typemeta/TEnumType.cpp @@ -1,7 +1,6 @@ #include #include #include -#include #include #include #include @@ -68,14 +67,14 @@ void bind_mrpt_typemeta_TEnumType(std::function< pybind11::module &(std::string cl.def("assign", (struct mrpt::typemeta::internal::bimap & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); } { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_hwdrivers_CGenericSensor_TSensorState_std_string_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); - cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); - cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); - cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); - cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::hwdrivers::CGenericSensor::TSensorState &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::hwdrivers::CGenericSensor::TSensorState &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::hwdrivers::CGenericSensor::TSensorState &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::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 & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); + pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_obs_CActionRobotMovement2D_TDrawSampleMotionModel_std_string_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); + cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); + cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); + cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); + cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::obs::CActionRobotMovement2D::TDrawSampleMotionModel &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::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 & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } diff --git a/python/src/mrpt/typemeta/TEnumType_1.cpp b/python/src/mrpt/typemeta/TEnumType_1.cpp index 945c04d467..6e29b1b376 100644 --- a/python/src/mrpt/typemeta/TEnumType_1.cpp +++ b/python/src/mrpt/typemeta/TEnumType_1.cpp @@ -1,8 +1,8 @@ #include #include +#include #include #include -#include #include #include #include @@ -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_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_hwdrivers_CGenericSensor_TSensorState_std_string_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); + cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); + cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); + cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); + cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::hwdrivers::CGenericSensor::TSensorState &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::hwdrivers::CGenericSensor::TSensorState &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::hwdrivers::CGenericSensor::TSensorState &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::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 & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_poses_TInterpolatorMethod_std_string_t", ""); cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); @@ -79,15 +90,4 @@ void bind_mrpt_typemeta_TEnumType_1(std::function< pybind11::module &(std::strin cl.def("insert", (void (mrpt::typemeta::internal::bimap::*)(const enum mrpt::img::DistortionModel &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::insert(const enum mrpt::img::DistortionModel &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v")); cl.def("assign", (struct mrpt::typemeta::internal::bimap & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_opengl_TCullFace_std_string_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); - cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); - cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); - cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); - cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::opengl::TCullFace &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::opengl::TCullFace &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::opengl::TCullFace &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::insert(const enum mrpt::opengl::TCullFace &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v")); - cl.def("assign", (struct mrpt::typemeta::internal::bimap & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } } diff --git a/python/src/mrpt/typemeta/TEnumType_2.cpp b/python/src/mrpt/typemeta/TEnumType_2.cpp index 9a73f68bfd..064c4f70f8 100644 --- a/python/src/mrpt/typemeta/TEnumType_2.cpp +++ b/python/src/mrpt/typemeta/TEnumType_2.cpp @@ -3,8 +3,8 @@ #include #include #include -#include #include +#include #include #include // __str__ #include @@ -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_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_opengl_TCullFace_std_string_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); + cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); + cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); + cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); + cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::opengl::TCullFace &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::opengl::TCullFace &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::opengl::TCullFace &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::insert(const enum mrpt::opengl::TCullFace &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v")); + cl.def("assign", (struct mrpt::typemeta::internal::bimap & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_hwdrivers_TCameraType_std_string_t", ""); cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); @@ -68,15 +79,4 @@ void bind_mrpt_typemeta_TEnumType_2(std::function< pybind11::module &(std::strin cl.def("insert", (void (mrpt::typemeta::internal::bimap::*)(const enum mrpt::hwdrivers::CGPSInterface::PARSERS &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::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 & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_hwdrivers_CVelodyneScanner_model_t_std_string_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); - cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); - cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); - cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); - cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::hwdrivers::CVelodyneScanner::model_t &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::hwdrivers::CVelodyneScanner::model_t &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::hwdrivers::CVelodyneScanner::model_t &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::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 & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } } diff --git a/python/src/mrpt/typemeta/TEnumType_3.cpp b/python/src/mrpt/typemeta/TEnumType_3.cpp index 08d2648d6a..e79b014553 100644 --- a/python/src/mrpt/typemeta/TEnumType_3.cpp +++ b/python/src/mrpt/typemeta/TEnumType_3.cpp @@ -3,7 +3,6 @@ #include #include #include -#include #include #include #include // __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_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_hwdrivers_CVelodyneScanner_model_t_std_string_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); + cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); + cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); + cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); + cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::hwdrivers::CVelodyneScanner::model_t &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::hwdrivers::CVelodyneScanner::model_t &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::hwdrivers::CVelodyneScanner::model_t &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::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 & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 pybind11::class_, std::shared_ptr>> 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(); } ) ); @@ -68,15 +78,4 @@ void bind_mrpt_typemeta_TEnumType_3(std::function< pybind11::module &(std::strin cl.def("insert", (void (mrpt::typemeta::internal::bimap::*)(const enum mrpt::maps::CHeightGridMap2D::TMapRepresentation &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::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 & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_maps_COccupancyGridMap2D_TLikelihoodMethod_std_string_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); - cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); - cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); - cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); - cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::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 & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } } diff --git a/python/src/mrpt/typemeta/TEnumType_4.cpp b/python/src/mrpt/typemeta/TEnumType_4.cpp index 26ace27f83..7105b1edbc 100644 --- a/python/src/mrpt/typemeta/TEnumType_4.cpp +++ b/python/src/mrpt/typemeta/TEnumType_4.cpp @@ -1,11 +1,11 @@ #include #include +#include #include #include #include -#include +#include #include -#include #include // __str__ #include @@ -24,6 +24,17 @@ void bind_mrpt_typemeta_TEnumType_4(std::function< pybind11::module &(std::string const &namespace_) > &M) { + { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_maps_COccupancyGridMap2D_TLikelihoodMethod_std_string_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); + cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); + cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); + cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); + cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::maps::COccupancyGridMap2D::TLikelihoodMethod &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::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 & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_maps_COccupancyGridMap3D_TLikelihoodMethod_std_string_t", ""); cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); @@ -58,36 +69,14 @@ void bind_mrpt_typemeta_TEnumType_4(std::function< pybind11::module &(std::strin cl.def("assign", (struct mrpt::typemeta::internal::bimap & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); } { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_vision_TKeyPointMethod_std_string_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); - cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); - cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); - cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); - cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::vision::TKeyPointMethod &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::vision::TKeyPointMethod &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::vision::TKeyPointMethod &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::insert(const enum mrpt::vision::TKeyPointMethod &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v")); - cl.def("assign", (struct mrpt::typemeta::internal::bimap & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_vision_TDescriptorType_std_string_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); - cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); - cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); - cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); - cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::vision::TDescriptorType &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::vision::TDescriptorType &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::vision::TDescriptorType &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::insert(const enum mrpt::vision::TDescriptorType &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v")); - cl.def("assign", (struct mrpt::typemeta::internal::bimap & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_slam_CGridMapAligner_TAlignerMethod_std_string_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); - cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); - cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); - cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); - cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::slam::CGridMapAligner::TAlignerMethod &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::slam::CGridMapAligner::TAlignerMethod &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::slam::CGridMapAligner::TAlignerMethod &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::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 & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); + pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_obs_CActionRobotMovement3D_TDrawSampleMotionModel_std_string_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); + cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); + cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); + cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); + cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::obs::CActionRobotMovement3D::TDrawSampleMotionModel &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::direct(const enum mrpt::obs::CActionRobotMovement3D::TDrawSampleMotionModel &, std::string &) const --> bool", pybind11::arg("k"), pybind11::arg("out_v")); + cl.def("inverse", (bool (mrpt::typemeta::internal::bimap::*)(const std::string &, enum mrpt::obs::CActionRobotMovement3D::TDrawSampleMotionModel &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::inverse(const std::string &, enum mrpt::obs::CActionRobotMovement3D::TDrawSampleMotionModel &) const --> bool", pybind11::arg("v"), pybind11::arg("out_k")); + cl.def("insert", (void (mrpt::typemeta::internal::bimap::*)(const enum mrpt::obs::CActionRobotMovement3D::TDrawSampleMotionModel &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::insert(const enum mrpt::obs::CActionRobotMovement3D::TDrawSampleMotionModel &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v")); + cl.def("assign", (struct mrpt::typemeta::internal::bimap & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } diff --git a/python/src/mrpt/typemeta/TEnumType_5.cpp b/python/src/mrpt/typemeta/TEnumType_5.cpp index 912329d4a9..6de0df691b 100644 --- a/python/src/mrpt/typemeta/TEnumType_5.cpp +++ b/python/src/mrpt/typemeta/TEnumType_5.cpp @@ -1,9 +1,11 @@ #include #include #include +#include #include #include #include +#include #include // __str__ #include @@ -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_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_vision_TKeyPointMethod_std_string_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); + cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); + cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); + cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); + cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::vision::TKeyPointMethod &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::vision::TKeyPointMethod &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::vision::TKeyPointMethod &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::insert(const enum mrpt::vision::TKeyPointMethod &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v")); + cl.def("assign", (struct mrpt::typemeta::internal::bimap & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_vision_TDescriptorType_std_string_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); + cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); + cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); + cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); + cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::vision::TDescriptorType &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::vision::TDescriptorType &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::vision::TDescriptorType &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::insert(const enum mrpt::vision::TDescriptorType &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v")); + cl.def("assign", (struct mrpt::typemeta::internal::bimap & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_slam_CGridMapAligner_TAlignerMethod_std_string_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); + cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); + cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); + cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); + cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::slam::CGridMapAligner::TAlignerMethod &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::slam::CGridMapAligner::TAlignerMethod &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::slam::CGridMapAligner::TAlignerMethod &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::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 & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_slam_similarity_method_t_std_string_t", ""); cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); @@ -55,15 +90,4 @@ void bind_mrpt_typemeta_TEnumType_5(std::function< pybind11::module &(std::strin cl.def("insert", (void (mrpt::typemeta::internal::bimap::*)(const enum mrpt::slam::TDataAssociationMethod &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::insert(const enum mrpt::slam::TDataAssociationMethod &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v")); cl.def("assign", (struct mrpt::typemeta::internal::bimap & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_slam_TDataAssociationMetric_std_string_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); - cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); - cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); - cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); - cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::slam::TDataAssociationMetric &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::slam::TDataAssociationMetric &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::slam::TDataAssociationMetric &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::insert(const enum mrpt::slam::TDataAssociationMetric &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v")); - cl.def("assign", (struct mrpt::typemeta::internal::bimap & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } } diff --git a/python/src/mrpt/typemeta/TEnumType_6.cpp b/python/src/mrpt/typemeta/TEnumType_6.cpp index 9e20724844..325f4afdbf 100644 --- a/python/src/mrpt/typemeta/TEnumType_6.cpp +++ b/python/src/mrpt/typemeta/TEnumType_6.cpp @@ -1,7 +1,6 @@ #include #include -#include -#include +#include #include #include // __str__ #include @@ -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_, std::shared_ptr>> cl(M("mrpt::typemeta"), "TEnumType_mrpt_bayes_TKFMethod_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::typemeta::TEnumType(); } ) ); - cl.def_static("name2value", (enum mrpt::bayes::TKFMethod (*)(const std::string &)) &mrpt::typemeta::TEnumType::name2value, "C++: mrpt::typemeta::TEnumType::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::value2name, "C++: mrpt::typemeta::TEnumType::value2name(const enum mrpt::bayes::TKFMethod) --> std::string", pybind11::arg("val")); - cl.def_static("getBimap", (struct mrpt::typemeta::internal::bimap & (*)()) &mrpt::typemeta::TEnumType::getBimap, "C++: mrpt::typemeta::TEnumType::getBimap() --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic); - } - { // mrpt::typemeta::TEnumType file:mrpt/typemeta/TEnumType.h line:94 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta"), "TEnumType_mrpt_system_VerbosityLevel_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::typemeta::TEnumType(); } ) ); - cl.def_static("name2value", (enum mrpt::system::VerbosityLevel (*)(const std::string &)) &mrpt::typemeta::TEnumType::name2value, "C++: mrpt::typemeta::TEnumType::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::value2name, "C++: mrpt::typemeta::TEnumType::value2name(const enum mrpt::system::VerbosityLevel) --> std::string", pybind11::arg("val")); - cl.def_static("getBimap", (struct mrpt::typemeta::internal::bimap & (*)()) &mrpt::typemeta::TEnumType::getBimap, "C++: mrpt::typemeta::TEnumType::getBimap() --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic); + { // mrpt::typemeta::internal::bimap file:mrpt/typemeta/TEnumType.h line:22 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta::internal"), "bimap_mrpt_slam_TDataAssociationMetric_std_string_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::typemeta::internal::bimap(); } ) ); + cl.def( pybind11::init( [](mrpt::typemeta::internal::bimap const &o){ return new mrpt::typemeta::internal::bimap(o); } ) ); + cl.def_readwrite("m_k2v", &mrpt::typemeta::internal::bimap::m_k2v); + cl.def_readwrite("m_v2k", &mrpt::typemeta::internal::bimap::m_v2k); + cl.def("direct", (bool (mrpt::typemeta::internal::bimap::*)(const enum mrpt::slam::TDataAssociationMetric &, std::string &) const) &mrpt::typemeta::internal::bimap::direct, "C++: mrpt::typemeta::internal::bimap::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::*)(const std::string &, enum mrpt::slam::TDataAssociationMetric &) const) &mrpt::typemeta::internal::bimap::inverse, "C++: mrpt::typemeta::internal::bimap::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::*)(const enum mrpt::slam::TDataAssociationMetric &, const std::string &)) &mrpt::typemeta::internal::bimap::insert, "C++: mrpt::typemeta::internal::bimap::insert(const enum mrpt::slam::TDataAssociationMetric &, const std::string &) --> void", pybind11::arg("k"), pybind11::arg("v")); + cl.def("assign", (struct mrpt::typemeta::internal::bimap & (mrpt::typemeta::internal::bimap::*)(const struct mrpt::typemeta::internal::bimap &)) &mrpt::typemeta::internal::bimap::operator=, "C++: mrpt::typemeta::internal::bimap::operator=(const struct mrpt::typemeta::internal::bimap &) --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } diff --git a/python/src/mrpt/typemeta/TEnumType_7.cpp b/python/src/mrpt/typemeta/TEnumType_7.cpp new file mode 100644 index 0000000000..28bdb567db --- /dev/null +++ b/python/src/mrpt/typemeta/TEnumType_7.cpp @@ -0,0 +1,38 @@ +#include +#include +#include +#include +#include +#include // __str__ +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#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_, std::shared_ptr>> cl(M("mrpt::typemeta"), "TEnumType_mrpt_bayes_TKFMethod_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::typemeta::TEnumType(); } ) ); + cl.def_static("name2value", (enum mrpt::bayes::TKFMethod (*)(const std::string &)) &mrpt::typemeta::TEnumType::name2value, "C++: mrpt::typemeta::TEnumType::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::value2name, "C++: mrpt::typemeta::TEnumType::value2name(const enum mrpt::bayes::TKFMethod) --> std::string", pybind11::arg("val")); + cl.def_static("getBimap", (struct mrpt::typemeta::internal::bimap & (*)()) &mrpt::typemeta::TEnumType::getBimap, "C++: mrpt::typemeta::TEnumType::getBimap() --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic); + } + { // mrpt::typemeta::TEnumType file:mrpt/typemeta/TEnumType.h line:94 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::typemeta"), "TEnumType_mrpt_system_VerbosityLevel_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::typemeta::TEnumType(); } ) ); + cl.def_static("name2value", (enum mrpt::system::VerbosityLevel (*)(const std::string &)) &mrpt::typemeta::TEnumType::name2value, "C++: mrpt::typemeta::TEnumType::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::value2name, "C++: mrpt::typemeta::TEnumType::value2name(const enum mrpt::system::VerbosityLevel) --> std::string", pybind11::arg("val")); + cl.def_static("getBimap", (struct mrpt::typemeta::internal::bimap & (*)()) &mrpt::typemeta::TEnumType::getBimap, "C++: mrpt::typemeta::TEnumType::getBimap() --> struct mrpt::typemeta::internal::bimap &", pybind11::return_value_policy::automatic); + } +} diff --git a/python/src/pymrpt.cpp b/python/src/pymrpt.cpp index b0dd90f7db..8b91d63ff2 100644 --- a/python/src/pymrpt.cpp +++ b/python/src/pymrpt.cpp @@ -52,6 +52,7 @@ void bind_mrpt_typemeta_TEnumType_3(std::function< pybind11::module &(std::strin void bind_mrpt_typemeta_TEnumType_4(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_typemeta_TEnumType_5(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_typemeta_TEnumType_6(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_mrpt_typemeta_TEnumType_7(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_serialization_CArchive(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_serialization_CArchive_1(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_serialization_CArchive_2(std::function< pybind11::module &(std::string const &namespace_) > &M); @@ -207,7 +208,6 @@ void bind_unknown_unknown_4(std::function< pybind11::module &(std::string const void bind_unknown_unknown_5(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_unknown_unknown_6(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_unknown_unknown_7(std::function< pybind11::module &(std::string const &namespace_) > &M); -void bind_unknown_unknown_8(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_obs_CObservationGPS(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_hwdrivers_CGPSInterface(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_containers_MT_buffer(std::function< pybind11::module &(std::string const &namespace_) > &M); @@ -313,9 +313,9 @@ void bind_mrpt_nav_reactive_CReactiveNavigationSystem3D(std::function< pybind11: void bind_mrpt_nav_tpspace_CPTG_DiffDrive_C(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_nav_tpspace_CPTG_DiffDrive_alpha(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_obs_CActionRobotMovement3D(std::function< pybind11::module &(std::string const &namespace_) > &M); -void bind_mrpt_obs_CObservationBatteryState(std::function< pybind11::module &(std::string const &namespace_) > &M); -void bind_mrpt_obs_CObservationOdometry(std::function< pybind11::module &(std::string const &namespace_) > &M); -void bind_mrpt_obs_CRawlog(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_mrpt_obs_CObservation3DScene(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_mrpt_obs_CObservationBearingRange(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_mrpt_obs_CObservationRobotPose(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_obs_format_externals_filename(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_obs_stock_observations(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_opengl_CArrow(std::function< pybind11::module &(std::string const &namespace_) > &M); @@ -483,6 +483,7 @@ PYBIND11_MODULE(pymrpt, root_module) { bind_mrpt_typemeta_TEnumType_4(M); bind_mrpt_typemeta_TEnumType_5(M); bind_mrpt_typemeta_TEnumType_6(M); + bind_mrpt_typemeta_TEnumType_7(M); bind_mrpt_serialization_CArchive(M); bind_mrpt_serialization_CArchive_1(M); bind_mrpt_serialization_CArchive_2(M); @@ -638,7 +639,6 @@ PYBIND11_MODULE(pymrpt, root_module) { bind_unknown_unknown_5(M); bind_unknown_unknown_6(M); bind_unknown_unknown_7(M); - bind_unknown_unknown_8(M); bind_mrpt_obs_CObservationGPS(M); bind_mrpt_hwdrivers_CGPSInterface(M); bind_mrpt_containers_MT_buffer(M); @@ -744,9 +744,9 @@ PYBIND11_MODULE(pymrpt, root_module) { bind_mrpt_nav_tpspace_CPTG_DiffDrive_C(M); bind_mrpt_nav_tpspace_CPTG_DiffDrive_alpha(M); bind_mrpt_obs_CActionRobotMovement3D(M); - bind_mrpt_obs_CObservationBatteryState(M); - bind_mrpt_obs_CObservationOdometry(M); - bind_mrpt_obs_CRawlog(M); + bind_mrpt_obs_CObservation3DScene(M); + bind_mrpt_obs_CObservationBearingRange(M); + bind_mrpt_obs_CObservationRobotPose(M); bind_mrpt_obs_format_externals_filename(M); bind_mrpt_obs_stock_observations(M); bind_mrpt_opengl_CArrow(M); diff --git a/python/src/pymrpt.sources b/python/src/pymrpt.sources index d182f5c286..69c04e8439 100644 --- a/python/src/pymrpt.sources +++ b/python/src/pymrpt.sources @@ -42,6 +42,7 @@ mrpt/typemeta/TEnumType_3.cpp mrpt/typemeta/TEnumType_4.cpp mrpt/typemeta/TEnumType_5.cpp mrpt/typemeta/TEnumType_6.cpp +mrpt/typemeta/TEnumType_7.cpp mrpt/serialization/CArchive.cpp mrpt/serialization/CArchive_1.cpp mrpt/serialization/CArchive_2.cpp @@ -197,7 +198,6 @@ unknown/unknown_4.cpp unknown/unknown_5.cpp unknown/unknown_6.cpp unknown/unknown_7.cpp -unknown/unknown_8.cpp mrpt/obs/CObservationGPS.cpp mrpt/hwdrivers/CGPSInterface.cpp mrpt/containers/MT_buffer.cpp @@ -303,9 +303,9 @@ mrpt/nav/reactive/CReactiveNavigationSystem3D.cpp mrpt/nav/tpspace/CPTG_DiffDrive_C.cpp mrpt/nav/tpspace/CPTG_DiffDrive_alpha.cpp mrpt/obs/CActionRobotMovement3D.cpp -mrpt/obs/CObservationBatteryState.cpp -mrpt/obs/CObservationOdometry.cpp -mrpt/obs/CRawlog.cpp +mrpt/obs/CObservation3DScene.cpp +mrpt/obs/CObservationBearingRange.cpp +mrpt/obs/CObservationRobotPose.cpp mrpt/obs/format_externals_filename.cpp mrpt/obs/stock_observations.cpp mrpt/opengl/CArrow.cpp diff --git a/python/src/unknown/unknown_1.cpp b/python/src/unknown/unknown_1.cpp index 13ae97a18d..89f605469f 100644 --- a/python/src/unknown/unknown_1.cpp +++ b/python/src/unknown/unknown_1.cpp @@ -28,96 +28,6 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// 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(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(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(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(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(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(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(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(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(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(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(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return gnss_message::fixEndianness(); - } -}; - // mrpt::obs::gnss::Message_NMEA_VTG file: line:177 struct PyCallBack_mrpt_obs_gnss_Message_NMEA_VTG : public mrpt::obs::gnss::Message_NMEA_VTG { using mrpt::obs::gnss::Message_NMEA_VTG::Message_NMEA_VTG; @@ -255,56 +165,6 @@ struct PyCallBack_mrpt_obs_gnss_Message_NMEA_ZDA : public mrpt::obs::gnss::Messa void bind_unknown_unknown_1(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::gnss::Message_NMEA_GLL file: line:104 - pybind11::class_, 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_> 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_, 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_> 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("")); - } - - } { // mrpt::obs::gnss::Message_NMEA_VTG file: line:177 pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NMEA_VTG, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NMEA_VTG", "NMEA datum: VTG. \n mrpt::obs::CObservationGPS "); cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_VTG(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_VTG(); } ) ); @@ -391,4 +251,15 @@ void bind_unknown_unknown_1(std::function< pybind11::module &(std::string const cl.def("fixEndianness", (void (mrpt::obs::gnss::nv_oem6_header_t::*)()) &mrpt::obs::gnss::nv_oem6_header_t::fixEndianness, "C++: mrpt::obs::gnss::nv_oem6_header_t::fixEndianness() --> void"); cl.def("assign", (struct mrpt::obs::gnss::nv_oem6_header_t & (mrpt::obs::gnss::nv_oem6_header_t::*)(const struct mrpt::obs::gnss::nv_oem6_header_t &)) &mrpt::obs::gnss::nv_oem6_header_t::operator=, "C++: mrpt::obs::gnss::nv_oem6_header_t::operator=(const struct mrpt::obs::gnss::nv_oem6_header_t &) --> struct mrpt::obs::gnss::nv_oem6_header_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); } + { // mrpt::obs::gnss::nv_oem6_short_header_t file: line:59 + pybind11::class_> cl(M("mrpt::obs::gnss"), "nv_oem6_short_header_t", "Novatel OEM6 short header structure \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](mrpt::obs::gnss::nv_oem6_short_header_t const &o){ return new mrpt::obs::gnss::nv_oem6_short_header_t(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::nv_oem6_short_header_t(); } ) ); + cl.def_readwrite("msg_len", &mrpt::obs::gnss::nv_oem6_short_header_t::msg_len); + cl.def_readwrite("msg_id", &mrpt::obs::gnss::nv_oem6_short_header_t::msg_id); + cl.def_readwrite("week", &mrpt::obs::gnss::nv_oem6_short_header_t::week); + cl.def_readwrite("ms_in_week", &mrpt::obs::gnss::nv_oem6_short_header_t::ms_in_week); + cl.def("fixEndianness", (void (mrpt::obs::gnss::nv_oem6_short_header_t::*)()) &mrpt::obs::gnss::nv_oem6_short_header_t::fixEndianness, "C++: mrpt::obs::gnss::nv_oem6_short_header_t::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::nv_oem6_short_header_t & (mrpt::obs::gnss::nv_oem6_short_header_t::*)(const struct mrpt::obs::gnss::nv_oem6_short_header_t &)) &mrpt::obs::gnss::nv_oem6_short_header_t::operator=, "C++: mrpt::obs::gnss::nv_oem6_short_header_t::operator=(const struct mrpt::obs::gnss::nv_oem6_short_header_t &) --> struct mrpt::obs::gnss::nv_oem6_short_header_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } } diff --git a/python/src/unknown/unknown_2.cpp b/python/src/unknown/unknown_2.cpp index 8069c8df7e..e215e9221a 100644 --- a/python/src/unknown/unknown_2.cpp +++ b/python/src/unknown/unknown_2.cpp @@ -1,5 +1,7 @@ -#include -#include // __str__ +#include +#include +#include +#include #include #include @@ -16,15 +18,41 @@ void bind_unknown_unknown_2(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::gnss::nv_oem6_short_header_t file: line:59 - pybind11::class_> cl(M("mrpt::obs::gnss"), "nv_oem6_short_header_t", "Novatel OEM6 short header structure \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](mrpt::obs::gnss::nv_oem6_short_header_t const &o){ return new mrpt::obs::gnss::nv_oem6_short_header_t(o); } ) ); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::nv_oem6_short_header_t(); } ) ); - cl.def_readwrite("msg_len", &mrpt::obs::gnss::nv_oem6_short_header_t::msg_len); - cl.def_readwrite("msg_id", &mrpt::obs::gnss::nv_oem6_short_header_t::msg_id); - cl.def_readwrite("week", &mrpt::obs::gnss::nv_oem6_short_header_t::week); - cl.def_readwrite("ms_in_week", &mrpt::obs::gnss::nv_oem6_short_header_t::ms_in_week); - cl.def("fixEndianness", (void (mrpt::obs::gnss::nv_oem6_short_header_t::*)()) &mrpt::obs::gnss::nv_oem6_short_header_t::fixEndianness, "C++: mrpt::obs::gnss::nv_oem6_short_header_t::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::nv_oem6_short_header_t & (mrpt::obs::gnss::nv_oem6_short_header_t::*)(const struct mrpt::obs::gnss::nv_oem6_short_header_t &)) &mrpt::obs::gnss::nv_oem6_short_header_t::operator=, "C++: mrpt::obs::gnss::nv_oem6_short_header_t::operator=(const struct mrpt::obs::gnss::nv_oem6_short_header_t &) --> struct mrpt::obs::gnss::nv_oem6_short_header_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } + // mrpt::obs::gnss::nv_oem6_position_type::nv_position_type_t file: line:88 + pybind11::enum_(M("mrpt::obs::gnss::nv_oem6_position_type"), "nv_position_type_t", pybind11::arithmetic(), "Novatel OEM6 firmware reference, table 84; Novatel SPAN on OEM6 firmware\n manual, table 26. ") + .value("NONE", mrpt::obs::gnss::nv_oem6_position_type::NONE) + .value("FIXEDPOS", mrpt::obs::gnss::nv_oem6_position_type::FIXEDPOS) + .value("FIXEDHEIGHT", mrpt::obs::gnss::nv_oem6_position_type::FIXEDHEIGHT) + .value("Reserved", mrpt::obs::gnss::nv_oem6_position_type::Reserved) + .value("FLOATCONV", mrpt::obs::gnss::nv_oem6_position_type::FLOATCONV) + .value("WIDELANE", mrpt::obs::gnss::nv_oem6_position_type::WIDELANE) + .value("NARROWLANE", mrpt::obs::gnss::nv_oem6_position_type::NARROWLANE) + .value("DOPPLER_VELOCITY", mrpt::obs::gnss::nv_oem6_position_type::DOPPLER_VELOCITY) + .value("SINGLE", mrpt::obs::gnss::nv_oem6_position_type::SINGLE) + .value("PSRDIFF", mrpt::obs::gnss::nv_oem6_position_type::PSRDIFF) + .value("WAAS", mrpt::obs::gnss::nv_oem6_position_type::WAAS) + .value("PROPAGATED", mrpt::obs::gnss::nv_oem6_position_type::PROPAGATED) + .value("OMNISTAR", mrpt::obs::gnss::nv_oem6_position_type::OMNISTAR) + .value("L1_FLOAT", mrpt::obs::gnss::nv_oem6_position_type::L1_FLOAT) + .value("IONOFREE_FLOAT", mrpt::obs::gnss::nv_oem6_position_type::IONOFREE_FLOAT) + .value("NARROW_FLOAT", mrpt::obs::gnss::nv_oem6_position_type::NARROW_FLOAT) + .value("L1_INT", mrpt::obs::gnss::nv_oem6_position_type::L1_INT) + .value("WIDE_INT", mrpt::obs::gnss::nv_oem6_position_type::WIDE_INT) + .value("NARROW_INT", mrpt::obs::gnss::nv_oem6_position_type::NARROW_INT) + .value("RTK_DIRECT_INS", mrpt::obs::gnss::nv_oem6_position_type::RTK_DIRECT_INS) + .value("INS", mrpt::obs::gnss::nv_oem6_position_type::INS) + .value("INS_PSRSP", mrpt::obs::gnss::nv_oem6_position_type::INS_PSRSP) + .value("INS_PSRDIFF", mrpt::obs::gnss::nv_oem6_position_type::INS_PSRDIFF) + .value("INS_RTKFLOAT", mrpt::obs::gnss::nv_oem6_position_type::INS_RTKFLOAT) + .value("INS_RTKFIXED", mrpt::obs::gnss::nv_oem6_position_type::INS_RTKFIXED) + .value("OMNISTAR_HP", mrpt::obs::gnss::nv_oem6_position_type::OMNISTAR_HP) + .value("OMNISTAR_XP", mrpt::obs::gnss::nv_oem6_position_type::OMNISTAR_XP) + .value("CDGPS", mrpt::obs::gnss::nv_oem6_position_type::CDGPS) + .export_values(); + +; + + // mrpt::obs::gnss::nv_oem6_position_type::enum2str(int) file: line:120 + M("mrpt::obs::gnss::nv_oem6_position_type").def("enum2str", (const std::string & (*)(int)) &mrpt::obs::gnss::nv_oem6_position_type::enum2str, "for nv_position_type_t \n\nC++: mrpt::obs::gnss::nv_oem6_position_type::enum2str(int) --> const std::string &", pybind11::return_value_policy::automatic, pybind11::arg("val")); + } diff --git a/python/src/unknown/unknown_3.cpp b/python/src/unknown/unknown_3.cpp index 72ad141a27..bf1d60b1fd 100644 --- a/python/src/unknown/unknown_3.cpp +++ b/python/src/unknown/unknown_3.cpp @@ -18,41 +18,32 @@ void bind_unknown_unknown_3(std::function< pybind11::module &(std::string const &namespace_) > &M) { - // mrpt::obs::gnss::nv_oem6_position_type::nv_position_type_t file: line:88 - pybind11::enum_(M("mrpt::obs::gnss::nv_oem6_position_type"), "nv_position_type_t", pybind11::arithmetic(), "Novatel OEM6 firmware reference, table 84; Novatel SPAN on OEM6 firmware\n manual, table 26. ") - .value("NONE", mrpt::obs::gnss::nv_oem6_position_type::NONE) - .value("FIXEDPOS", mrpt::obs::gnss::nv_oem6_position_type::FIXEDPOS) - .value("FIXEDHEIGHT", mrpt::obs::gnss::nv_oem6_position_type::FIXEDHEIGHT) - .value("Reserved", mrpt::obs::gnss::nv_oem6_position_type::Reserved) - .value("FLOATCONV", mrpt::obs::gnss::nv_oem6_position_type::FLOATCONV) - .value("WIDELANE", mrpt::obs::gnss::nv_oem6_position_type::WIDELANE) - .value("NARROWLANE", mrpt::obs::gnss::nv_oem6_position_type::NARROWLANE) - .value("DOPPLER_VELOCITY", mrpt::obs::gnss::nv_oem6_position_type::DOPPLER_VELOCITY) - .value("SINGLE", mrpt::obs::gnss::nv_oem6_position_type::SINGLE) - .value("PSRDIFF", mrpt::obs::gnss::nv_oem6_position_type::PSRDIFF) - .value("WAAS", mrpt::obs::gnss::nv_oem6_position_type::WAAS) - .value("PROPAGATED", mrpt::obs::gnss::nv_oem6_position_type::PROPAGATED) - .value("OMNISTAR", mrpt::obs::gnss::nv_oem6_position_type::OMNISTAR) - .value("L1_FLOAT", mrpt::obs::gnss::nv_oem6_position_type::L1_FLOAT) - .value("IONOFREE_FLOAT", mrpt::obs::gnss::nv_oem6_position_type::IONOFREE_FLOAT) - .value("NARROW_FLOAT", mrpt::obs::gnss::nv_oem6_position_type::NARROW_FLOAT) - .value("L1_INT", mrpt::obs::gnss::nv_oem6_position_type::L1_INT) - .value("WIDE_INT", mrpt::obs::gnss::nv_oem6_position_type::WIDE_INT) - .value("NARROW_INT", mrpt::obs::gnss::nv_oem6_position_type::NARROW_INT) - .value("RTK_DIRECT_INS", mrpt::obs::gnss::nv_oem6_position_type::RTK_DIRECT_INS) - .value("INS", mrpt::obs::gnss::nv_oem6_position_type::INS) - .value("INS_PSRSP", mrpt::obs::gnss::nv_oem6_position_type::INS_PSRSP) - .value("INS_PSRDIFF", mrpt::obs::gnss::nv_oem6_position_type::INS_PSRDIFF) - .value("INS_RTKFLOAT", mrpt::obs::gnss::nv_oem6_position_type::INS_RTKFLOAT) - .value("INS_RTKFIXED", mrpt::obs::gnss::nv_oem6_position_type::INS_RTKFIXED) - .value("OMNISTAR_HP", mrpt::obs::gnss::nv_oem6_position_type::OMNISTAR_HP) - .value("OMNISTAR_XP", mrpt::obs::gnss::nv_oem6_position_type::OMNISTAR_XP) - .value("CDGPS", mrpt::obs::gnss::nv_oem6_position_type::CDGPS) + // mrpt::obs::gnss::nv_oem6_solution_status::nv_solution_status_t file: line:126 + pybind11::enum_(M("mrpt::obs::gnss::nv_oem6_solution_status"), "nv_solution_status_t", pybind11::arithmetic(), "Novatel OEM6 firmware reference, table 85 ") + .value("SOL_COMPUTED", mrpt::obs::gnss::nv_oem6_solution_status::SOL_COMPUTED) + .value("INSUFFICIENT_OBS", mrpt::obs::gnss::nv_oem6_solution_status::INSUFFICIENT_OBS) + .value("NO_CONVERGENCE", mrpt::obs::gnss::nv_oem6_solution_status::NO_CONVERGENCE) + .value("SINGULARITY", mrpt::obs::gnss::nv_oem6_solution_status::SINGULARITY) + .value("COV_TRACE", mrpt::obs::gnss::nv_oem6_solution_status::COV_TRACE) + .value("TEST_DIST", mrpt::obs::gnss::nv_oem6_solution_status::TEST_DIST) + .value("COLD_START", mrpt::obs::gnss::nv_oem6_solution_status::COLD_START) + .value("V_H_LIMIT", mrpt::obs::gnss::nv_oem6_solution_status::V_H_LIMIT) + .value("VARIANCE", mrpt::obs::gnss::nv_oem6_solution_status::VARIANCE) + .value("RESIDUALS", mrpt::obs::gnss::nv_oem6_solution_status::RESIDUALS) + .value("DELTA_POS", mrpt::obs::gnss::nv_oem6_solution_status::DELTA_POS) + .value("NEGATIVE_VAR", mrpt::obs::gnss::nv_oem6_solution_status::NEGATIVE_VAR) + .value("INTEGRITY_WARNING", mrpt::obs::gnss::nv_oem6_solution_status::INTEGRITY_WARNING) + .value("INS_INACTIVE", mrpt::obs::gnss::nv_oem6_solution_status::INS_INACTIVE) + .value("INS_ALIGNING", mrpt::obs::gnss::nv_oem6_solution_status::INS_ALIGNING) + .value("INS_BAD", mrpt::obs::gnss::nv_oem6_solution_status::INS_BAD) + .value("IMU_UNPLUGGED", mrpt::obs::gnss::nv_oem6_solution_status::IMU_UNPLUGGED) + .value("PENDING", mrpt::obs::gnss::nv_oem6_solution_status::PENDING) + .value("INVALID_FIX", mrpt::obs::gnss::nv_oem6_solution_status::INVALID_FIX) .export_values(); ; - // mrpt::obs::gnss::nv_oem6_position_type::enum2str(int) file: line:120 - M("mrpt::obs::gnss::nv_oem6_position_type").def("enum2str", (const std::string & (*)(int)) &mrpt::obs::gnss::nv_oem6_position_type::enum2str, "for nv_position_type_t \n\nC++: mrpt::obs::gnss::nv_oem6_position_type::enum2str(int) --> const std::string &", pybind11::return_value_policy::automatic, pybind11::arg("val")); + // mrpt::obs::gnss::nv_oem6_solution_status::enum2str(int) file: line:170 + M("mrpt::obs::gnss::nv_oem6_solution_status").def("enum2str", (const std::string & (*)(int)) &mrpt::obs::gnss::nv_oem6_solution_status::enum2str, "for nv_solution_status_t \n\nC++: mrpt::obs::gnss::nv_oem6_solution_status::enum2str(int) --> const std::string &", pybind11::return_value_policy::automatic, pybind11::arg("val")); } diff --git a/python/src/unknown/unknown_4.cpp b/python/src/unknown/unknown_4.cpp index 28c00d2ea4..11b3d780a4 100644 --- a/python/src/unknown/unknown_4.cpp +++ b/python/src/unknown/unknown_4.cpp @@ -18,32 +18,21 @@ void bind_unknown_unknown_4(std::function< pybind11::module &(std::string const &namespace_) > &M) { - // mrpt::obs::gnss::nv_oem6_solution_status::nv_solution_status_t file: line:126 - pybind11::enum_(M("mrpt::obs::gnss::nv_oem6_solution_status"), "nv_solution_status_t", pybind11::arithmetic(), "Novatel OEM6 firmware reference, table 85 ") - .value("SOL_COMPUTED", mrpt::obs::gnss::nv_oem6_solution_status::SOL_COMPUTED) - .value("INSUFFICIENT_OBS", mrpt::obs::gnss::nv_oem6_solution_status::INSUFFICIENT_OBS) - .value("NO_CONVERGENCE", mrpt::obs::gnss::nv_oem6_solution_status::NO_CONVERGENCE) - .value("SINGULARITY", mrpt::obs::gnss::nv_oem6_solution_status::SINGULARITY) - .value("COV_TRACE", mrpt::obs::gnss::nv_oem6_solution_status::COV_TRACE) - .value("TEST_DIST", mrpt::obs::gnss::nv_oem6_solution_status::TEST_DIST) - .value("COLD_START", mrpt::obs::gnss::nv_oem6_solution_status::COLD_START) - .value("V_H_LIMIT", mrpt::obs::gnss::nv_oem6_solution_status::V_H_LIMIT) - .value("VARIANCE", mrpt::obs::gnss::nv_oem6_solution_status::VARIANCE) - .value("RESIDUALS", mrpt::obs::gnss::nv_oem6_solution_status::RESIDUALS) - .value("DELTA_POS", mrpt::obs::gnss::nv_oem6_solution_status::DELTA_POS) - .value("NEGATIVE_VAR", mrpt::obs::gnss::nv_oem6_solution_status::NEGATIVE_VAR) - .value("INTEGRITY_WARNING", mrpt::obs::gnss::nv_oem6_solution_status::INTEGRITY_WARNING) - .value("INS_INACTIVE", mrpt::obs::gnss::nv_oem6_solution_status::INS_INACTIVE) - .value("INS_ALIGNING", mrpt::obs::gnss::nv_oem6_solution_status::INS_ALIGNING) - .value("INS_BAD", mrpt::obs::gnss::nv_oem6_solution_status::INS_BAD) - .value("IMU_UNPLUGGED", mrpt::obs::gnss::nv_oem6_solution_status::IMU_UNPLUGGED) - .value("PENDING", mrpt::obs::gnss::nv_oem6_solution_status::PENDING) - .value("INVALID_FIX", mrpt::obs::gnss::nv_oem6_solution_status::INVALID_FIX) + // mrpt::obs::gnss::nv_oem6_ins_status_type::nv_ins_status_type_t file: line:175 + pybind11::enum_(M("mrpt::obs::gnss::nv_oem6_ins_status_type"), "nv_ins_status_type_t", pybind11::arithmetic(), "Novatel SPAN on OEM6 firmware reference, table 33 ") + .value("INS_INACTIVE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_INACTIVE) + .value("INS_ALIGNING", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_ALIGNING) + .value("INS_HIGH_VARIANCE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_HIGH_VARIANCE) + .value("INS_SOLUTION_GOOD", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_SOLUTION_GOOD) + .value("INS_SOLUTION_FREE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_SOLUTION_FREE) + .value("INS_ALIGNMENT_COMPLETE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_ALIGNMENT_COMPLETE) + .value("DETERMINING_ORIENTATION", mrpt::obs::gnss::nv_oem6_ins_status_type::DETERMINING_ORIENTATION) + .value("WAITING_INITIALPOS", mrpt::obs::gnss::nv_oem6_ins_status_type::WAITING_INITIALPOS) .export_values(); ; - // mrpt::obs::gnss::nv_oem6_solution_status::enum2str(int) file: line:170 - M("mrpt::obs::gnss::nv_oem6_solution_status").def("enum2str", (const std::string & (*)(int)) &mrpt::obs::gnss::nv_oem6_solution_status::enum2str, "for nv_solution_status_t \n\nC++: mrpt::obs::gnss::nv_oem6_solution_status::enum2str(int) --> const std::string &", pybind11::return_value_policy::automatic, pybind11::arg("val")); + // mrpt::obs::gnss::nv_oem6_ins_status_type::enum2str(int) file: line:198 + M("mrpt::obs::gnss::nv_oem6_ins_status_type").def("enum2str", (const std::string & (*)(int)) &mrpt::obs::gnss::nv_oem6_ins_status_type::enum2str, "for nv_ins_status_type_t \n\nC++: mrpt::obs::gnss::nv_oem6_ins_status_type::enum2str(int) --> const std::string &", pybind11::return_value_policy::automatic, pybind11::arg("val")); } diff --git a/python/src/unknown/unknown_5.cpp b/python/src/unknown/unknown_5.cpp index b539543008..3d02cbc1c9 100644 --- a/python/src/unknown/unknown_5.cpp +++ b/python/src/unknown/unknown_5.cpp @@ -1,7 +1,16 @@ +#include #include #include -#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include #include +#include #include #include @@ -16,23 +25,408 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif +// mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME file: line:203 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME : public mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME { + using mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::Message_NV_OEM6_GENERIC_FRAME; + + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_GENERIC_FRAME::fixEndianness(); + } + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_GENERIC_FRAME::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(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_GENERIC_FRAME::internal_readFromStream(a0); + } +}; + +// mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME file: line:224 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME : public mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME { + using mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::Message_NV_OEM6_GENERIC_SHORT_FRAME; + + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness(); + } + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_GENERIC_SHORT_FRAME::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(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_GENERIC_SHORT_FRAME::internal_readFromStream(a0); + } +}; + +// mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:80 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS : public mrpt::obs::gnss::Message_NV_OEM6_BESTPOS { + using mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::Message_NV_OEM6_BESTPOS; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_BESTPOS::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(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_BESTPOS::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_BESTPOS::fixEndianness(); + } +}; + +// mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:86 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS : public mrpt::obs::gnss::Message_NV_OEM6_INSPVAS { + using mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::Message_NV_OEM6_INSPVAS; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_INSPVAS::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(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_INSPVAS::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_INSPVAS::fixEndianness(); + } +}; + +// mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:92 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS : public mrpt::obs::gnss::Message_NV_OEM6_INSCOVS { + using mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::Message_NV_OEM6_INSCOVS; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_INSCOVS::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(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_INSCOVS::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_INSCOVS::fixEndianness(); + } +}; + +// mrpt::obs::gnss::Message_NV_OEM6_RANGECMP file: line:379 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP : public mrpt::obs::gnss::Message_NV_OEM6_RANGECMP { + using mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::Message_NV_OEM6_RANGECMP; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_RANGECMP::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(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_RANGECMP::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return gnss_message::fixEndianness(); + } +}; + void bind_unknown_unknown_5(std::function< pybind11::module &(std::string const &namespace_) > &M) { - // mrpt::obs::gnss::nv_oem6_ins_status_type::nv_ins_status_type_t file: line:175 - pybind11::enum_(M("mrpt::obs::gnss::nv_oem6_ins_status_type"), "nv_ins_status_type_t", pybind11::arithmetic(), "Novatel SPAN on OEM6 firmware reference, table 33 ") - .value("INS_INACTIVE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_INACTIVE) - .value("INS_ALIGNING", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_ALIGNING) - .value("INS_HIGH_VARIANCE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_HIGH_VARIANCE) - .value("INS_SOLUTION_GOOD", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_SOLUTION_GOOD) - .value("INS_SOLUTION_FREE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_SOLUTION_FREE) - .value("INS_ALIGNMENT_COMPLETE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_ALIGNMENT_COMPLETE) - .value("DETERMINING_ORIENTATION", mrpt::obs::gnss::nv_oem6_ins_status_type::DETERMINING_ORIENTATION) - .value("WAITING_INITIALPOS", mrpt::obs::gnss::nv_oem6_ins_status_type::WAITING_INITIALPOS) - .export_values(); - -; - - // mrpt::obs::gnss::nv_oem6_ins_status_type::enum2str(int) file: line:198 - M("mrpt::obs::gnss::nv_oem6_ins_status_type").def("enum2str", (const std::string & (*)(int)) &mrpt::obs::gnss::nv_oem6_ins_status_type::enum2str, "for nv_ins_status_type_t \n\nC++: mrpt::obs::gnss::nv_oem6_ins_status_type::enum2str(int) --> const std::string &", pybind11::return_value_policy::automatic, pybind11::arg("val")); + { // mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME file: line:203 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_GENERIC_FRAME", "Novatel generic frame (to store frames without a parser at the present\n time). \n\n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::header); + cl.def_readwrite("msg_body", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::msg_body); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME & (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME &)) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME file: line:224 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_GENERIC_SHORT_FRAME", "Novatel generic short-header frame (to store frames without a parser at the\n present time). \n\n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::header); + cl.def_readwrite("msg_body", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::msg_body); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME & (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &)) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:80 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_BESTPOS", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_BESTPOS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS & (mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS &)) &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t file: line:137 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::header); + cl.def_readwrite("solution_stat", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::solution_stat); + cl.def_readwrite("position_type", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::position_type); + cl.def_readwrite("lat", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lat); + cl.def_readwrite("lon", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lon); + cl.def_readwrite("hgt", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::hgt); + cl.def_readwrite("undulation", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::undulation); + cl.def_readwrite("datum_id", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::datum_id); + cl.def_readwrite("lat_sigma", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lat_sigma); + cl.def_readwrite("lon_sigma", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lon_sigma); + cl.def_readwrite("hgt_sigma", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::hgt_sigma); + cl.def_readwrite("diff_age", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::diff_age); + cl.def_readwrite("sol_age", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::sol_age); + cl.def_readwrite("num_sats_tracked", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_tracked); + cl.def_readwrite("num_sats_sol", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_sol); + cl.def_readwrite("num_sats_sol_L1", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_sol_L1); + cl.def_readwrite("num_sats_sol_multi", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_sol_multi); + cl.def_readwrite("reserved", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::reserved); + cl.def_readwrite("ext_sol_stat", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::ext_sol_stat); + cl.def_readwrite("galileo_beidou_mask", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::galileo_beidou_mask); + cl.def_readwrite("gps_glonass_mask", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::gps_glonass_mask); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + } + { // mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:86 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_INSPVAS", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSPVAS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS & (mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS &)) &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t file: line:137 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::header); + cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::week); + cl.def_readwrite("seconds_in_week", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::seconds_in_week); + cl.def_readwrite("lat", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::lat); + cl.def_readwrite("lon", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::lon); + cl.def_readwrite("hgt", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::hgt); + cl.def_readwrite("vel_north", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::vel_north); + cl.def_readwrite("vel_east", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::vel_east); + cl.def_readwrite("vel_up", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::vel_up); + cl.def_readwrite("roll", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::roll); + cl.def_readwrite("pitch", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::pitch); + cl.def_readwrite("azimuth", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::azimuth); + cl.def_readwrite("ins_status", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::ins_status); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + } + { // mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:92 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_INSCOVS", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSCOVS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS & (mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS &)) &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t file: line:137 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::header); + cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::week); + cl.def_readwrite("seconds_in_week", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::seconds_in_week); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + } + { // mrpt::obs::gnss::Message_NV_OEM6_RANGECMP file: line:379 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RANGECMP", "Novatel frame: NV_OEM6_RANGECMP. \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RANGECMP(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RANGECMP const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RANGECMP(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::header); + cl.def_readwrite("num_obs", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::num_obs); + cl.def_readwrite("obs_data", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::obs_data); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP & (mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP &)) &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::TCompressedRangeLog file: line:385 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TCompressedRangeLog", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::TCompressedRangeLog(); } ) ); + } + } } diff --git a/python/src/unknown/unknown_6.cpp b/python/src/unknown/unknown_6.cpp index 05fb332486..035dc51eb6 100644 --- a/python/src/unknown/unknown_6.cpp +++ b/python/src/unknown/unknown_6.cpp @@ -25,26 +25,13 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME file: line:203 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME : public mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME { - using mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::Message_NV_OEM6_GENERIC_FRAME; +// mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:98 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS { + using mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::Message_NV_OEM6_RXSTATUS; - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_GENERIC_FRAME::fixEndianness(); - } void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -53,11 +40,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME : public mrpt::obs } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_GENERIC_FRAME::internal_writeToStream(a0); + return Message_NV_OEM6_RXSTATUS::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(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -66,17 +53,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME : public mrpt::obs } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_GENERIC_FRAME::internal_readFromStream(a0); + return Message_NV_OEM6_RXSTATUS::internal_readFromStream(a0); } -}; - -// mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME file: line:224 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME : public mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME { - using mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::Message_NV_OEM6_GENERIC_SHORT_FRAME; - void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -85,43 +66,17 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME : public mrp } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness(); - } - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_GENERIC_SHORT_FRAME::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(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_GENERIC_SHORT_FRAME::internal_readFromStream(a0); + return Message_NV_OEM6_RXSTATUS::fixEndianness(); } }; -// mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:86 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS : public mrpt::obs::gnss::Message_NV_OEM6_BESTPOS { - using mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::Message_NV_OEM6_BESTPOS; +// mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:104 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM : public mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM { + using mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::Message_NV_OEM6_RAWEPHEM; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -130,11 +85,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_BESTPOS::internal_writeToStream(a0); + return Message_NV_OEM6_RAWEPHEM::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(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -143,11 +98,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_BESTPOS::internal_readFromStream(a0); + return Message_NV_OEM6_RAWEPHEM::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -156,30 +111,30 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_BESTPOS::fixEndianness(); + return Message_NV_OEM6_RAWEPHEM::fixEndianness(); } }; -// mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:92 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS : public mrpt::obs::gnss::Message_NV_OEM6_INSPVAS { - using mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::Message_NV_OEM6_INSPVAS; +// mrpt::obs::gnss::Message_NV_OEM6_VERSION file: line:462 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION : public mrpt::obs::gnss::Message_NV_OEM6_VERSION { + using mrpt::obs::gnss::Message_NV_OEM6_VERSION::Message_NV_OEM6_VERSION; - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { - auto o = overload.operator()(a0); + auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { static pybind11::detail::override_caster_t caster; return pybind11::detail::cast_ref(std::move(o), caster); } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_INSPVAS::internal_writeToStream(a0); + return Message_NV_OEM6_VERSION::fixEndianness(); } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -188,30 +143,30 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_INSPVAS::internal_readFromStream(a0); + return Message_NV_OEM6_VERSION::internal_writeToStream(a0); } - void fixEndianness() override { + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { - auto o = overload.operator()(); + auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { static pybind11::detail::override_caster_t caster; return pybind11::detail::cast_ref(std::move(o), caster); } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_INSPVAS::fixEndianness(); + return Message_NV_OEM6_VERSION::internal_readFromStream(a0); } }; -// mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:98 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS : public mrpt::obs::gnss::Message_NV_OEM6_INSCOVS { - using mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::Message_NV_OEM6_INSCOVS; +// mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:110 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS { + using mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::Message_NV_OEM6_RAWIMUS; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -220,11 +175,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_INSCOVS::internal_writeToStream(a0); + return Message_NV_OEM6_RAWIMUS::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(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -233,11 +188,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_INSCOVS::internal_readFromStream(a0); + return Message_NV_OEM6_RAWIMUS::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -246,17 +201,17 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_INSCOVS::fixEndianness(); + return Message_NV_OEM6_RAWIMUS::fixEndianness(); } }; -// mrpt::obs::gnss::Message_NV_OEM6_RANGECMP file: line:379 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP : public mrpt::obs::gnss::Message_NV_OEM6_RANGECMP { - using mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::Message_NV_OEM6_RANGECMP; +// mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:116 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss::Message_NV_OEM6_MARKPOS { + using mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::Message_NV_OEM6_MARKPOS; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -265,11 +220,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RANGECMP::internal_writeToStream(a0); + return Message_NV_OEM6_MARKPOS::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(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -278,11 +233,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RANGECMP::internal_readFromStream(a0); + return Message_NV_OEM6_MARKPOS::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -291,141 +246,159 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return gnss_message::fixEndianness(); + return Message_NV_OEM6_MARKPOS::fixEndianness(); } }; void bind_unknown_unknown_6(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME file: line:203 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_GENERIC_FRAME", "Novatel generic frame (to store frames without a parser at the present\n time). \n\n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::header); - cl.def_readwrite("msg_body", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::msg_body); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME & (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME &)) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - { // mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME file: line:224 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_GENERIC_SHORT_FRAME", "Novatel generic short-header frame (to store frames without a parser at the\n present time). \n\n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::header); - cl.def_readwrite("msg_body", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::msg_body); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME & (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &)) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:98 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RXSTATUS", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS & (mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS &)) &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t file: line:137 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::header); + cl.def_readwrite("error", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::error); + cl.def_readwrite("num_stats", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::num_stats); + cl.def_readwrite("rxstat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat); + cl.def_readwrite("rxstat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat_pri); + cl.def_readwrite("rxstat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat_set); + cl.def_readwrite("rxstat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat_clear); + cl.def_readwrite("aux1stat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat); + cl.def_readwrite("aux1stat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat_pri); + cl.def_readwrite("aux1stat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat_set); + cl.def_readwrite("aux1stat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat_clear); + cl.def_readwrite("aux2stat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat); + cl.def_readwrite("aux2stat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat_pri); + cl.def_readwrite("aux2stat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat_set); + cl.def_readwrite("aux2stat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat_clear); + cl.def_readwrite("aux3stat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat); + cl.def_readwrite("aux3stat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat_pri); + cl.def_readwrite("aux3stat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat_set); + cl.def_readwrite("aux3stat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat_clear); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + } - { // mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:86 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_BESTPOS", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_BESTPOS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS & (mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS &)) &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:104 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RAWEPHEM", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::*)()) &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM & (mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t file: line:172 + { // mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t file: line:137 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::header); - cl.def_readwrite("solution_stat", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::solution_stat); - cl.def_readwrite("position_type", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::position_type); - cl.def_readwrite("lat", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lat); - cl.def_readwrite("lon", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lon); - cl.def_readwrite("hgt", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::hgt); - cl.def_readwrite("undulation", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::undulation); - cl.def_readwrite("datum_id", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::datum_id); - cl.def_readwrite("lat_sigma", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lat_sigma); - cl.def_readwrite("lon_sigma", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lon_sigma); - cl.def_readwrite("hgt_sigma", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::hgt_sigma); - cl.def_readwrite("diff_age", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::diff_age); - cl.def_readwrite("sol_age", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::sol_age); - cl.def_readwrite("num_sats_tracked", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_tracked); - cl.def_readwrite("num_sats_sol", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_sol); - cl.def_readwrite("num_sats_sol_L1", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_sol_L1); - cl.def_readwrite("num_sats_sol_multi", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_sol_multi); - cl.def_readwrite("reserved", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::reserved); - cl.def_readwrite("ext_sol_stat", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::ext_sol_stat); - cl.def_readwrite("galileo_beidou_mask", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::galileo_beidou_mask); - cl.def_readwrite("gps_glonass_mask", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::gps_glonass_mask); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::header); + cl.def_readwrite("sat_prn", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::sat_prn); + cl.def_readwrite("ref_week", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::ref_week); + cl.def_readwrite("ref_secs", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::ref_secs); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t & (mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } - { // mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:92 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_INSPVAS", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSPVAS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS & (mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS &)) &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_VERSION file: line:462 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_VERSION", "Novatel frame: NV_OEM6_VERSION. \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_VERSION(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_VERSION const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_VERSION(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::header); + cl.def_readwrite("num_comps", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::num_comps); + cl.def_readwrite("components", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::components); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::crc); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_VERSION::*)()) &mrpt::obs::gnss::Message_NV_OEM6_VERSION::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_VERSION::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_VERSION & (mrpt::obs::gnss::Message_NV_OEM6_VERSION::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_VERSION &)) &mrpt::obs::gnss::Message_NV_OEM6_VERSION::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_VERSION::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_VERSION &) --> struct mrpt::obs::gnss::Message_NV_OEM6_VERSION &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t file: line:172 + { // mrpt::obs::gnss::Message_NV_OEM6_VERSION::TComponentVersion file: line:468 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::header); - cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::week); - cl.def_readwrite("seconds_in_week", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::seconds_in_week); - cl.def_readwrite("lat", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::lat); - cl.def_readwrite("lon", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::lon); - cl.def_readwrite("hgt", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::hgt); - cl.def_readwrite("vel_north", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::vel_north); - cl.def_readwrite("vel_east", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::vel_east); - cl.def_readwrite("vel_up", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::vel_up); - cl.def_readwrite("roll", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::roll); - cl.def_readwrite("pitch", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::pitch); - cl.def_readwrite("azimuth", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::azimuth); - cl.def_readwrite("ins_status", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::ins_status); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + pybind11::class_> cl(enclosing_class, "TComponentVersion", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_VERSION::TComponentVersion(); } ) ); + cl.def_readwrite("type", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::TComponentVersion::type); } } - { // mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:98 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_INSCOVS", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSCOVS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS & (mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS &)) &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:110 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RAWIMUS", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS & (mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t file: line:172 + { // mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t file: line:137 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::header); - cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::week); - cl.def_readwrite("seconds_in_week", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::seconds_in_week); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::header); + cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::week); + cl.def_readwrite("week_seconds", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::week_seconds); + cl.def_readwrite("imu_status", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::imu_status); + cl.def_readwrite("accel_z", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::accel_z); + cl.def_readwrite("accel_y_neg", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::accel_y_neg); + cl.def_readwrite("accel_x", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::accel_x); + cl.def_readwrite("gyro_z", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::gyro_z); + cl.def_readwrite("gyro_y_neg", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::gyro_y_neg); + cl.def_readwrite("gyro_x", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::gyro_x); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } - { // mrpt::obs::gnss::Message_NV_OEM6_RANGECMP file: line:379 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RANGECMP", "Novatel frame: NV_OEM6_RANGECMP. \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RANGECMP(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RANGECMP const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RANGECMP(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::header); - cl.def_readwrite("num_obs", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::num_obs); - cl.def_readwrite("obs_data", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::obs_data); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP & (mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP &)) &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:116 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARKPOS", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKPOS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS & (mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::TCompressedRangeLog file: line:385 + { // mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t file: line:137 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "TCompressedRangeLog", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::TCompressedRangeLog(); } ) ); + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::header); + cl.def_readwrite("solution_stat", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::solution_stat); + cl.def_readwrite("position_type", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::position_type); + cl.def_readwrite("lat", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lat); + cl.def_readwrite("lon", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lon); + cl.def_readwrite("hgt", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::hgt); + cl.def_readwrite("undulation", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::undulation); + cl.def_readwrite("datum_id", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::datum_id); + cl.def_readwrite("lat_sigma", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lat_sigma); + cl.def_readwrite("lon_sigma", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lon_sigma); + cl.def_readwrite("hgt_sigma", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::hgt_sigma); + cl.def_readwrite("diff_age", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::diff_age); + cl.def_readwrite("sol_age", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::sol_age); + cl.def_readwrite("num_sats_tracked", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_tracked); + cl.def_readwrite("num_sats_sol", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_sol); + cl.def_readwrite("num_sats_sol_L1", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_sol_L1); + cl.def_readwrite("num_sats_sol_multi", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_sol_multi); + cl.def_readwrite("reserved", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::reserved); + cl.def_readwrite("ext_sol_stat", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::ext_sol_stat); + cl.def_readwrite("galileo_beidou_mask", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::galileo_beidou_mask); + cl.def_readwrite("gps_glonass_mask", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::gps_glonass_mask); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } diff --git a/python/src/unknown/unknown_7.cpp b/python/src/unknown/unknown_7.cpp index 8cbcc882ef..cbe00113ab 100644 --- a/python/src/unknown/unknown_7.cpp +++ b/python/src/unknown/unknown_7.cpp @@ -25,13 +25,13 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:104 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS { - using mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::Message_NV_OEM6_RXSTATUS; +// mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:122 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME : public mrpt::obs::gnss::Message_NV_OEM6_MARKTIME { + using mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::Message_NV_OEM6_MARKTIME; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -40,11 +40,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RXSTATUS::internal_writeToStream(a0); + return Message_NV_OEM6_MARKTIME::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(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -53,11 +53,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RXSTATUS::internal_readFromStream(a0); + return Message_NV_OEM6_MARKTIME::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -66,17 +66,17 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RXSTATUS::fixEndianness(); + return Message_NV_OEM6_MARKTIME::fixEndianness(); } }; -// mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:110 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM : public mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM { - using mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::Message_NV_OEM6_RAWEPHEM; +// mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:128 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME : public mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME { + using mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::Message_NV_OEM6_MARK2TIME; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -85,11 +85,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RAWEPHEM::internal_writeToStream(a0); + return Message_NV_OEM6_MARK2TIME::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(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -98,11 +98,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RAWEPHEM::internal_readFromStream(a0); + return Message_NV_OEM6_MARK2TIME::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -111,30 +111,30 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RAWEPHEM::fixEndianness(); + return Message_NV_OEM6_MARK2TIME::fixEndianness(); } }; -// mrpt::obs::gnss::Message_NV_OEM6_VERSION file: line:462 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION : public mrpt::obs::gnss::Message_NV_OEM6_VERSION { - using mrpt::obs::gnss::Message_NV_OEM6_VERSION::Message_NV_OEM6_VERSION; +// mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:5 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC : public mrpt::obs::gnss::Message_NV_OEM6_IONUTC { + using mrpt::obs::gnss::Message_NV_OEM6_IONUTC::Message_NV_OEM6_IONUTC; - void fixEndianness() override { + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { - auto o = overload.operator()(); + auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { static pybind11::detail::override_caster_t caster; return pybind11::detail::cast_ref(std::move(o), caster); } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_VERSION::fixEndianness(); + return Message_NV_OEM6_IONUTC::internal_writeToStream(a0); } - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -143,30 +143,30 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_VERSION::internal_writeToStream(a0); + return Message_NV_OEM6_IONUTC::internal_readFromStream(a0); } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { - auto o = overload.operator()(a0); + auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { static pybind11::detail::override_caster_t caster; return pybind11::detail::cast_ref(std::move(o), caster); } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_VERSION::internal_readFromStream(a0); + return Message_NV_OEM6_IONUTC::fixEndianness(); } }; -// mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:116 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS { - using mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::Message_NV_OEM6_RAWIMUS; +// mrpt::obs::gnss::Message_TOPCON_PZS file: line:18 +struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS : public mrpt::obs::gnss::Message_TOPCON_PZS { + using mrpt::obs::gnss::Message_TOPCON_PZS::Message_TOPCON_PZS; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -175,11 +175,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RAWIMUS::internal_writeToStream(a0); + return Message_TOPCON_PZS::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(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -188,11 +188,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RAWIMUS::internal_readFromStream(a0); + return Message_TOPCON_PZS::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -201,17 +201,17 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RAWIMUS::fixEndianness(); + return gnss_message::fixEndianness(); } }; -// mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:122 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss::Message_NV_OEM6_MARKPOS { - using mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::Message_NV_OEM6_MARKPOS; +// mrpt::obs::gnss::Message_TOPCON_SATS file: line:90 +struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS : public mrpt::obs::gnss::Message_TOPCON_SATS { + using mrpt::obs::gnss::Message_TOPCON_SATS::Message_TOPCON_SATS; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -220,11 +220,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_MARKPOS::internal_writeToStream(a0); + return Message_TOPCON_SATS::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(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -233,11 +233,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_MARKPOS::internal_readFromStream(a0); + return Message_TOPCON_SATS::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -246,160 +246,142 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_MARKPOS::fixEndianness(); + return gnss_message::fixEndianness(); } }; void bind_unknown_unknown_7(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:104 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RXSTATUS", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS & (mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS &)) &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:122 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARKTIME", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKTIME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME & (mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t file: line:172 + { // mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t file: line:137 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::header); - cl.def_readwrite("error", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::error); - cl.def_readwrite("num_stats", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::num_stats); - cl.def_readwrite("rxstat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat); - cl.def_readwrite("rxstat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat_pri); - cl.def_readwrite("rxstat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat_set); - cl.def_readwrite("rxstat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat_clear); - cl.def_readwrite("aux1stat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat); - cl.def_readwrite("aux1stat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat_pri); - cl.def_readwrite("aux1stat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat_set); - cl.def_readwrite("aux1stat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat_clear); - cl.def_readwrite("aux2stat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat); - cl.def_readwrite("aux2stat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat_pri); - cl.def_readwrite("aux2stat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat_set); - cl.def_readwrite("aux2stat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat_clear); - cl.def_readwrite("aux3stat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat); - cl.def_readwrite("aux3stat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat_pri); - cl.def_readwrite("aux3stat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat_set); - cl.def_readwrite("aux3stat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat_clear); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::header); + cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::week); + cl.def_readwrite("week_seconds", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::week_seconds); + cl.def_readwrite("clock_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::clock_offset); + cl.def_readwrite("clock_offset_std", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::clock_offset_std); + cl.def_readwrite("utc_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::utc_offset); + cl.def_readwrite("clock_status", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::clock_status); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t & (mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } - { // mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:110 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RAWEPHEM", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::*)()) &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM & (mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:128 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARK2TIME", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME & (mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME &)) &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t file: line:172 + { // mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t file: line:137 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::header); - cl.def_readwrite("sat_prn", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::sat_prn); - cl.def_readwrite("ref_week", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::ref_week); - cl.def_readwrite("ref_secs", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::ref_secs); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t & (mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::header); + cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::week); + cl.def_readwrite("week_seconds", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::week_seconds); + cl.def_readwrite("clock_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::clock_offset); + cl.def_readwrite("clock_offset_std", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::clock_offset_std); + cl.def_readwrite("utc_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::utc_offset); + cl.def_readwrite("clock_status", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::clock_status); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t & (mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } - { // mrpt::obs::gnss::Message_NV_OEM6_VERSION file: line:462 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_VERSION", "Novatel frame: NV_OEM6_VERSION. \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_VERSION(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_VERSION const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_VERSION(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::header); - cl.def_readwrite("num_comps", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::num_comps); - cl.def_readwrite("components", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::components); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::crc); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_VERSION::*)()) &mrpt::obs::gnss::Message_NV_OEM6_VERSION::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_VERSION::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_VERSION & (mrpt::obs::gnss::Message_NV_OEM6_VERSION::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_VERSION &)) &mrpt::obs::gnss::Message_NV_OEM6_VERSION::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_VERSION::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_VERSION &) --> struct mrpt::obs::gnss::Message_NV_OEM6_VERSION &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:5 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_IONUTC", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_IONUTC const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_IONUTC::*)()) &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_IONUTC::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC & (mrpt::obs::gnss::Message_NV_OEM6_IONUTC::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC &)) &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_IONUTC::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC &) --> struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_VERSION::TComponentVersion file: line:468 + { // mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t file: line:137 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "TComponentVersion", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_VERSION::TComponentVersion(); } ) ); - cl.def_readwrite("type", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::TComponentVersion::type); + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::header); + cl.def_readwrite("a0", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a0); + cl.def_readwrite("a1", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a1); + cl.def_readwrite("a2", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a2); + cl.def_readwrite("a3", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a3); + cl.def_readwrite("b0", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b0); + cl.def_readwrite("b1", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b1); + cl.def_readwrite("b2", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b2); + cl.def_readwrite("b3", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b3); + cl.def_readwrite("utc_wn", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::utc_wn); + cl.def_readwrite("tot", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::tot); + cl.def_readwrite("A0", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::A0); + cl.def_readwrite("A1", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::A1); + cl.def_readwrite("wn_lsf", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::wn_lsf); + cl.def_readwrite("dn", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::dn); + cl.def_readwrite("deltat_ls", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::deltat_ls); + cl.def_readwrite("deltat_lsf", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::deltat_lsf); + cl.def_readwrite("reserved", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::reserved); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t & (mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } - { // mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:116 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RAWIMUS", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS & (mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t file: line:172 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::header); - cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::week); - cl.def_readwrite("week_seconds", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::week_seconds); - cl.def_readwrite("imu_status", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::imu_status); - cl.def_readwrite("accel_z", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::accel_z); - cl.def_readwrite("accel_y_neg", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::accel_y_neg); - cl.def_readwrite("accel_x", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::accel_x); - cl.def_readwrite("gyro_z", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::gyro_z); - cl.def_readwrite("gyro_y_neg", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::gyro_y_neg); - cl.def_readwrite("gyro_x", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::gyro_x); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - + { // mrpt::obs::gnss::Message_TOPCON_PZS file: line:18 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_TOPCON_PZS", "GPS datum for TopCon's mmGPS devices: PZS. \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_TOPCON_PZS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_TOPCON_PZS const &o){ return new mrpt::obs::gnss::Message_TOPCON_PZS(o); } ) ); + cl.def_readwrite("latitude_degrees", &mrpt::obs::gnss::Message_TOPCON_PZS::latitude_degrees); + cl.def_readwrite("longitude_degrees", &mrpt::obs::gnss::Message_TOPCON_PZS::longitude_degrees); + cl.def_readwrite("height_meters", &mrpt::obs::gnss::Message_TOPCON_PZS::height_meters); + cl.def_readwrite("RTK_height_meters", &mrpt::obs::gnss::Message_TOPCON_PZS::RTK_height_meters); + cl.def_readwrite("PSigma", &mrpt::obs::gnss::Message_TOPCON_PZS::PSigma); + cl.def_readwrite("angle_transmitter", &mrpt::obs::gnss::Message_TOPCON_PZS::angle_transmitter); + cl.def_readwrite("nId", &mrpt::obs::gnss::Message_TOPCON_PZS::nId); + cl.def_readwrite("Fix", &mrpt::obs::gnss::Message_TOPCON_PZS::Fix); + cl.def_readwrite("TXBattery", &mrpt::obs::gnss::Message_TOPCON_PZS::TXBattery); + cl.def_readwrite("RXBattery", &mrpt::obs::gnss::Message_TOPCON_PZS::RXBattery); + cl.def_readwrite("error", &mrpt::obs::gnss::Message_TOPCON_PZS::error); + cl.def_readwrite("hasCartesianPosVel", &mrpt::obs::gnss::Message_TOPCON_PZS::hasCartesianPosVel); + cl.def_readwrite("cartesian_x", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_x); + cl.def_readwrite("cartesian_y", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_y); + cl.def_readwrite("cartesian_z", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_z); + cl.def_readwrite("cartesian_vx", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_vx); + cl.def_readwrite("cartesian_vy", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_vy); + cl.def_readwrite("cartesian_vz", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_vz); + cl.def_readwrite("hasPosCov", &mrpt::obs::gnss::Message_TOPCON_PZS::hasPosCov); + cl.def_readwrite("pos_covariance", &mrpt::obs::gnss::Message_TOPCON_PZS::pos_covariance); + cl.def_readwrite("hasVelCov", &mrpt::obs::gnss::Message_TOPCON_PZS::hasVelCov); + cl.def_readwrite("vel_covariance", &mrpt::obs::gnss::Message_TOPCON_PZS::vel_covariance); + cl.def_readwrite("hasStats", &mrpt::obs::gnss::Message_TOPCON_PZS::hasStats); + cl.def_readwrite("stats_GPS_sats_used", &mrpt::obs::gnss::Message_TOPCON_PZS::stats_GPS_sats_used); + cl.def_readwrite("stats_GLONASS_sats_used", &mrpt::obs::gnss::Message_TOPCON_PZS::stats_GLONASS_sats_used); + cl.def_readwrite("stats_rtk_fix_progress", &mrpt::obs::gnss::Message_TOPCON_PZS::stats_rtk_fix_progress); + cl.def("assign", (struct mrpt::obs::gnss::Message_TOPCON_PZS & (mrpt::obs::gnss::Message_TOPCON_PZS::*)(const struct mrpt::obs::gnss::Message_TOPCON_PZS &)) &mrpt::obs::gnss::Message_TOPCON_PZS::operator=, "C++: mrpt::obs::gnss::Message_TOPCON_PZS::operator=(const struct mrpt::obs::gnss::Message_TOPCON_PZS &) --> struct mrpt::obs::gnss::Message_TOPCON_PZS &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:122 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARKPOS", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKPOS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS & (mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t file: line:172 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::header); - cl.def_readwrite("solution_stat", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::solution_stat); - cl.def_readwrite("position_type", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::position_type); - cl.def_readwrite("lat", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lat); - cl.def_readwrite("lon", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lon); - cl.def_readwrite("hgt", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::hgt); - cl.def_readwrite("undulation", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::undulation); - cl.def_readwrite("datum_id", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::datum_id); - cl.def_readwrite("lat_sigma", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lat_sigma); - cl.def_readwrite("lon_sigma", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lon_sigma); - cl.def_readwrite("hgt_sigma", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::hgt_sigma); - cl.def_readwrite("diff_age", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::diff_age); - cl.def_readwrite("sol_age", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::sol_age); - cl.def_readwrite("num_sats_tracked", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_tracked); - cl.def_readwrite("num_sats_sol", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_sol); - cl.def_readwrite("num_sats_sol_L1", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_sol_L1); - cl.def_readwrite("num_sats_sol_multi", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_sol_multi); - cl.def_readwrite("reserved", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::reserved); - cl.def_readwrite("ext_sol_stat", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::ext_sol_stat); - cl.def_readwrite("galileo_beidou_mask", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::galileo_beidou_mask); - cl.def_readwrite("gps_glonass_mask", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::gps_glonass_mask); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - + { // mrpt::obs::gnss::Message_TOPCON_SATS file: line:90 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_TOPCON_SATS", "TopCon mmGPS devices: SATS, a generic structure for statistics about tracked\n satelites and their positions. \n\n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_TOPCON_SATS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_TOPCON_SATS const &o){ return new mrpt::obs::gnss::Message_TOPCON_SATS(o); } ) ); + cl.def_readwrite("USIs", &mrpt::obs::gnss::Message_TOPCON_SATS::USIs); + cl.def_readwrite("ELs", &mrpt::obs::gnss::Message_TOPCON_SATS::ELs); + cl.def_readwrite("AZs", &mrpt::obs::gnss::Message_TOPCON_SATS::AZs); + cl.def("assign", (struct mrpt::obs::gnss::Message_TOPCON_SATS & (mrpt::obs::gnss::Message_TOPCON_SATS::*)(const struct mrpt::obs::gnss::Message_TOPCON_SATS &)) &mrpt::obs::gnss::Message_TOPCON_SATS::operator=, "C++: mrpt::obs::gnss::Message_TOPCON_SATS::operator=(const struct mrpt::obs::gnss::Message_TOPCON_SATS &) --> struct mrpt::obs::gnss::Message_TOPCON_SATS &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } diff --git a/python/src/unknown/unknown_8.cpp b/python/src/unknown/unknown_8.cpp deleted file mode 100644 index a475ccb6c0..0000000000 --- a/python/src/unknown/unknown_8.cpp +++ /dev/null @@ -1,387 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include // __str__ -#include -#include -#include - -#include -#include -#include -#include - - -#ifndef BINDER_PYBIND11_TYPE_CASTER - #define BINDER_PYBIND11_TYPE_CASTER - PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) - PYBIND11_DECLARE_HOLDER_TYPE(T, T*) - PYBIND11_MAKE_OPAQUE(std::shared_ptr) -#endif - -// mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:128 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME : public mrpt::obs::gnss::Message_NV_OEM6_MARKTIME { - using mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::Message_NV_OEM6_MARKTIME; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_MARKTIME::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(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_MARKTIME::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_MARKTIME::fixEndianness(); - } -}; - -// mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:5 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME : public mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME { - using mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::Message_NV_OEM6_MARK2TIME; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_MARK2TIME::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(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_MARK2TIME::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_MARK2TIME::fixEndianness(); - } -}; - -// mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:11 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC : public mrpt::obs::gnss::Message_NV_OEM6_IONUTC { - using mrpt::obs::gnss::Message_NV_OEM6_IONUTC::Message_NV_OEM6_IONUTC; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_IONUTC::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(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_IONUTC::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_IONUTC::fixEndianness(); - } -}; - -// mrpt::obs::gnss::Message_TOPCON_PZS file: line:18 -struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS : public mrpt::obs::gnss::Message_TOPCON_PZS { - using mrpt::obs::gnss::Message_TOPCON_PZS::Message_TOPCON_PZS; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_TOPCON_PZS::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(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_TOPCON_PZS::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return gnss_message::fixEndianness(); - } -}; - -// mrpt::obs::gnss::Message_TOPCON_SATS file: line:90 -struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS : public mrpt::obs::gnss::Message_TOPCON_SATS { - using mrpt::obs::gnss::Message_TOPCON_SATS::Message_TOPCON_SATS; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_TOPCON_SATS::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(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_TOPCON_SATS::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return gnss_message::fixEndianness(); - } -}; - -void bind_unknown_unknown_8(std::function< pybind11::module &(std::string const &namespace_) > &M) -{ - { // mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:128 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARKTIME", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKTIME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME & (mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t file: line:172 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::header); - cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::week); - cl.def_readwrite("week_seconds", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::week_seconds); - cl.def_readwrite("clock_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::clock_offset); - cl.def_readwrite("clock_offset_std", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::clock_offset_std); - cl.def_readwrite("utc_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::utc_offset); - cl.def_readwrite("clock_status", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::clock_status); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t & (mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - - } - { // mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:5 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARK2TIME", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME & (mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME &)) &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t file: line:172 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::header); - cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::week); - cl.def_readwrite("week_seconds", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::week_seconds); - cl.def_readwrite("clock_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::clock_offset); - cl.def_readwrite("clock_offset_std", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::clock_offset_std); - cl.def_readwrite("utc_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::utc_offset); - cl.def_readwrite("clock_status", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::clock_status); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t & (mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - - } - { // mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:11 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_IONUTC", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_IONUTC const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_IONUTC::*)()) &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_IONUTC::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC & (mrpt::obs::gnss::Message_NV_OEM6_IONUTC::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC &)) &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_IONUTC::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC &) --> struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t file: line:172 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::header); - cl.def_readwrite("a0", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a0); - cl.def_readwrite("a1", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a1); - cl.def_readwrite("a2", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a2); - cl.def_readwrite("a3", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a3); - cl.def_readwrite("b0", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b0); - cl.def_readwrite("b1", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b1); - cl.def_readwrite("b2", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b2); - cl.def_readwrite("b3", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b3); - cl.def_readwrite("utc_wn", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::utc_wn); - cl.def_readwrite("tot", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::tot); - cl.def_readwrite("A0", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::A0); - cl.def_readwrite("A1", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::A1); - cl.def_readwrite("wn_lsf", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::wn_lsf); - cl.def_readwrite("dn", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::dn); - cl.def_readwrite("deltat_ls", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::deltat_ls); - cl.def_readwrite("deltat_lsf", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::deltat_lsf); - cl.def_readwrite("reserved", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::reserved); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t & (mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - - } - { // mrpt::obs::gnss::Message_TOPCON_PZS file: line:18 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_TOPCON_PZS", "GPS datum for TopCon's mmGPS devices: PZS. \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_TOPCON_PZS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_TOPCON_PZS const &o){ return new mrpt::obs::gnss::Message_TOPCON_PZS(o); } ) ); - cl.def_readwrite("latitude_degrees", &mrpt::obs::gnss::Message_TOPCON_PZS::latitude_degrees); - cl.def_readwrite("longitude_degrees", &mrpt::obs::gnss::Message_TOPCON_PZS::longitude_degrees); - cl.def_readwrite("height_meters", &mrpt::obs::gnss::Message_TOPCON_PZS::height_meters); - cl.def_readwrite("RTK_height_meters", &mrpt::obs::gnss::Message_TOPCON_PZS::RTK_height_meters); - cl.def_readwrite("PSigma", &mrpt::obs::gnss::Message_TOPCON_PZS::PSigma); - cl.def_readwrite("angle_transmitter", &mrpt::obs::gnss::Message_TOPCON_PZS::angle_transmitter); - cl.def_readwrite("nId", &mrpt::obs::gnss::Message_TOPCON_PZS::nId); - cl.def_readwrite("Fix", &mrpt::obs::gnss::Message_TOPCON_PZS::Fix); - cl.def_readwrite("TXBattery", &mrpt::obs::gnss::Message_TOPCON_PZS::TXBattery); - cl.def_readwrite("RXBattery", &mrpt::obs::gnss::Message_TOPCON_PZS::RXBattery); - cl.def_readwrite("error", &mrpt::obs::gnss::Message_TOPCON_PZS::error); - cl.def_readwrite("hasCartesianPosVel", &mrpt::obs::gnss::Message_TOPCON_PZS::hasCartesianPosVel); - cl.def_readwrite("cartesian_x", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_x); - cl.def_readwrite("cartesian_y", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_y); - cl.def_readwrite("cartesian_z", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_z); - cl.def_readwrite("cartesian_vx", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_vx); - cl.def_readwrite("cartesian_vy", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_vy); - cl.def_readwrite("cartesian_vz", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_vz); - cl.def_readwrite("hasPosCov", &mrpt::obs::gnss::Message_TOPCON_PZS::hasPosCov); - cl.def_readwrite("pos_covariance", &mrpt::obs::gnss::Message_TOPCON_PZS::pos_covariance); - cl.def_readwrite("hasVelCov", &mrpt::obs::gnss::Message_TOPCON_PZS::hasVelCov); - cl.def_readwrite("vel_covariance", &mrpt::obs::gnss::Message_TOPCON_PZS::vel_covariance); - cl.def_readwrite("hasStats", &mrpt::obs::gnss::Message_TOPCON_PZS::hasStats); - cl.def_readwrite("stats_GPS_sats_used", &mrpt::obs::gnss::Message_TOPCON_PZS::stats_GPS_sats_used); - cl.def_readwrite("stats_GLONASS_sats_used", &mrpt::obs::gnss::Message_TOPCON_PZS::stats_GLONASS_sats_used); - cl.def_readwrite("stats_rtk_fix_progress", &mrpt::obs::gnss::Message_TOPCON_PZS::stats_rtk_fix_progress); - cl.def("assign", (struct mrpt::obs::gnss::Message_TOPCON_PZS & (mrpt::obs::gnss::Message_TOPCON_PZS::*)(const struct mrpt::obs::gnss::Message_TOPCON_PZS &)) &mrpt::obs::gnss::Message_TOPCON_PZS::operator=, "C++: mrpt::obs::gnss::Message_TOPCON_PZS::operator=(const struct mrpt::obs::gnss::Message_TOPCON_PZS &) --> struct mrpt::obs::gnss::Message_TOPCON_PZS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - { // mrpt::obs::gnss::Message_TOPCON_SATS file: line:90 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_TOPCON_SATS", "TopCon mmGPS devices: SATS, a generic structure for statistics about tracked\n satelites and their positions. \n\n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_TOPCON_SATS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_TOPCON_SATS const &o){ return new mrpt::obs::gnss::Message_TOPCON_SATS(o); } ) ); - cl.def_readwrite("USIs", &mrpt::obs::gnss::Message_TOPCON_SATS::USIs); - cl.def_readwrite("ELs", &mrpt::obs::gnss::Message_TOPCON_SATS::ELs); - cl.def_readwrite("AZs", &mrpt::obs::gnss::Message_TOPCON_SATS::AZs); - cl.def("assign", (struct mrpt::obs::gnss::Message_TOPCON_SATS & (mrpt::obs::gnss::Message_TOPCON_SATS::*)(const struct mrpt::obs::gnss::Message_TOPCON_SATS &)) &mrpt::obs::gnss::Message_TOPCON_SATS::operator=, "C++: mrpt::obs::gnss::Message_TOPCON_SATS::operator=(const struct mrpt::obs::gnss::Message_TOPCON_SATS &) --> struct mrpt::obs::gnss::Message_TOPCON_SATS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } -} diff --git a/version_prefix.txt b/version_prefix.txt index 0732d73472..efad03bd21 100644 --- a/version_prefix.txt +++ b/version_prefix.txt @@ -1,4 +1,4 @@ -2.11.11 +2.11.12 # IMPORTANT: This file is parsed by CMake, don't add any comment to # the first line. # This file is used in both Windows and Linux scripts to automatically