Go to the documentation of this file.
79 using namespace xsens;
189 return rcv.getDataShort();
200 return rcv.getDataShort();
211 return rcv.getDataShort();
239 snd.setBusId(
busId());
251 snd.setBusId(
busId());
269 snd.setBusId(
busId());
377 snd.setBusId(
busId());
382 return (
double)rcv.getDataFloat();
390 snd.setBusId(
busId());
391 snd.setDataShort((uint16_t)
id);
401 snd.setBusId(
busId());
406 return rcv.getDataShort();
414 snd.setBusId(
busId());
429 uint16_t hwv = rcv.getDataShort();
448 snd.setBusId(
busId());
458 result.resize(nofScenarios);
459 for (
XsSize i = 0; i < nofScenarios; ++i)
462 result[i].setType(type);
465 result[i].setFilterType(filterType);
473 result[i].setKind(kind.c_str());
487 if (left.type() == right.type())
488 return strcmp(left.label(), right.label()) < 0;
490 return left.type() < right.type();
503 const char* pc = (
const char*) rcv.getDataBuffer();
505 std::string result(pc ? pc :
" ", 20);
506 std::string::difference_type thingy = (std::string::difference_type) result.find(
" ");
508 result.erase(result.begin() + thingy, result.end());
539 snd.setBusId(
busId());
547 std::string fullMessageData((
const char*)rcv.getDataBuffer());
548 if (fullMessageData.empty())
550 auto numericFilter = rcv.getDataShort();
552 for (
auto currentProfile : profilesFromDevice)
554 if (currentProfile.type() == numericFilter)
555 return currentProfile;
562 fullMessageData = fullMessageData.substr(0, std::min(rcv.getDataSize(), fullMessageData.find(
' ')));
565 for (
auto currentProfile : profilesFromDevice)
567 if (currentProfile.label() == fullMessageData)
568 return currentProfile;
573 auto splitterPosition = fullMessageData.find(
'/');
574 if (splitterPosition != std::string::npos)
576 std::string combinedName;
577 auto firstProfileName = fullMessageData.substr(0, splitterPosition);
578 auto secondProfileName = fullMessageData.substr(splitterPosition + 1, fullMessageData.size());
580 for (
auto currentProfile : profilesFromDevice)
582 if (currentProfile.label() == firstProfileName)
583 firstProfile = currentProfile;
584 else if (currentProfile.label() == secondProfileName)
585 secondProfile = currentProfile;
588 combinedProfile = firstProfile;
590 combinedName.append(firstProfile.label()).append(
"/").append(secondProfile.label());
591 combinedProfile.setLabel(combinedName.c_str());
592 return combinedProfile;
608 return p.type() == profileType;
614 snd.setBusId(
busId());
615 snd.setDataShort((uint16_t)profileType);
633 XsFilterProfileArray::iterator item[2];
635 for (
auto currentProfile : profileList)
640 return currentProfile == p.label();
649 snd.setBusId(
busId());
650 snd.setDataBuffer((
const uint8_t*)profile.c_str(), profile.size());
694 snd.setBusId(
busId());
695 snd.setDataShort(duration);
708 uint8_t bid = (uint8_t)
busId();
713 snd.setDataFloat((
float) lla[0], 0);
714 snd.setDataFloat((
float) lla[1], 4);
715 snd.setDataFloat((
float) lla[2], 8);
731 for (
XsSize i = 0; i < 3; i++)
732 vec[i] = rcv.getDataDouble(i * 8);
759 return static_cast<XsErrorMode>(rcv.getDataShort());
772 snd.setBusId(
busId());
773 snd.setDataShort(em);
790 return rcv.getDataShort();
801 snd.setBusId(
busId());
802 snd.setDataShort(delay);
815 snd.setBusId(
busId());
826 snd.setBusId(
busId());
831 return XsSelfTestResult::create(rcv.getDataShort());
841 snd.setBusId(
busId());
856 int result = baseFrequency / (skipFactor + 1);
901 ptrdiff_t offset = code.findSubStr(hwtype);
902 while (offset >= 0 && code[(
unsigned int)offset] !=
'-')
908 return code.mid(0, (
unsigned int)offset);
@ XDOF_None
When set to 1, disables all option flags.
@ XEM_Ignore
Ignore all errors without warning.
XsFilterProfileArray readFilterProfilesFromDevice() const
Request the filter profiles headers from the hardware device and returns a vector with the found prof...
char m_filterType
The filter type.
XsErrorMode errorMode() const
struct XsFilterProfile XsFilterProfile
bool setErrorMode(XsErrorMode errorMode)
Set the error mode of the device.
#define XS_LEN_SETFILTERPROFILE
uint16_t m_filterProfile
The currently chosen filter profile.
XsDeviceId const & deviceId() const
Return the device ID of the device.
#define XS_LEN_LOCATIONID
A class that represents a vector of real numbers.
double accelerometerRange() const
virtual bool setLocationId(int id)
Set the location ID of the device.
XsDeviceOptionFlag deviceOptionFlags() const override
Returns the device option flags.
virtual ~MtDevice()
Destroys the MtDevice.
static XsString stripProductCode(const XsString &code)
Helper function to strip the hardware type from the product code.
virtual XsDeviceState deviceState() const
Return the state of this device.
@ XFPK_Additional
Indicates an additional profile.
XsFilterProfile m_hardwareFilterProfile
A hardware filter profile.
A list of XsFilterProfile values.
virtual bool storeAlignmentMatrix()
Store the current alignment matrix in the device.
@ XRM_None
No reset planned.
virtual bool XSNOEXPORT initialize()
virtual bool canDoOrientationResetInFirmware(XsResetMethod method)
Checks if this device can do orientation reset in firmware.
uint16_t stringSkipFactor() const override
Returns the skipfactor for string output.
An abstract internal struct of a device.
XsString productCode() const
Return the product code of the device.
XsSelfTestResult runSelfTest()
Run a self test.
int updateRateForDataIdentifier(XsDataIdentifier dataType) const override
Returns the currently configured update rate for the supplied dataType.
struct XsVersion XsVersion
bool setInitialPositionLLA(const XsVector &lla) override
Set the current sensor position.
virtual bool sendRawMessage(const XsMessage &message)
Send a message directly to the communicator.
struct XsOutputConfigurationArray XsOutputConfigurationArray
double headingOffset() const
The heading offset set for this device.
Contains the results of a self-test performed by an Xsens device.
XsVersion hardwareVersion() const
Return the hardware version of the device.
@ XMID_SetFilterProfile
Set the current filter profile.
#define XS_SYNC_CLOCK_US_TO_TICKS
@ XRM_DefaultInclination
Revert to default behaviour for inclination, undoes XRM_Inclination.
A list of XsString values.
virtual void updateFilterProfiles()
Updates the scenarios.
bool setRs485TransmissionDelay(uint16_t delay)
Set the RS485 acknowledge transmission delay of the device.
bool restoreFactoryDefaults()
Restore to factory default settings.
static const char * findHardwareType(const char *productCode)
bool setOnboardFilterProfile(int profileType) override
Sets the filter profile to use for computing orientations on the device.
XsIntArray gnssReceiverSettings() const override
Gets some GNSS receiver settings.
virtual int updateRateForDataIdentifier(XsDataIdentifier dataType) const
Returns the currently configured update rate for the supplied dataType.
@ XMID_ReqStringOutputType
uint32_t syncTicksToUs(uint32_t ticks) const
Convert mt sync ticks to microseconds.
uint16_t stringSamplePeriod() const override
Returns the sample period for string output.
virtual int busId() const
The bus ID for this device.
XsFilterProfile onboardFilterProfile() const override
Gets the filter profile in use by the device for computing orientations.
A list of XsOutputConfiguration values.
bool initialize() override
Initialize the Mt device using the supplied filter profiles.
uint8_t m_filterMinor
The filter minor version.
XsDataIdentifier
Defines the data identifiers.
Contains information about an available filter profile.
A base struct for a communication interface.
enum XsBaudRate XsBaudRate
Communication speed.
virtual XsDeviceConfiguration const &XSNOEXPORT deviceConfigurationConst() const
XsFilterProfileArray availableOnboardFilterProfiles() const override
Return the list of filter profiles available on the device.
#define XS_SYNC_CLOCK_TICKS_TO_US
Macros and types for use in the Xsens communication protocol and Xsens Device API classes.
uint16_t rs485TransmissionDelay() const
Return the RS485 acknowledge transmission delay of the device.
virtual void fetchAvailableHardwareScenarios()
Fetches available hardware scenarios.
#define XS_BID_BROADCAST
The bus broadcast bus identifier (all devices)
virtual bool restoreFactoryDefaults()
Restore the device to its factory default settings.
virtual XSNOEXPORT bool messageLooksSane(const XsMessage &msg) const
MtDevice(XsDeviceId const &id)
Constructs a standalone MtDevice with device Id id.
uint8_t m_filterMajor
The filter major version.
void writeDeviceSettingsToFile() override
Write the emts of the device to the open logfile.
struct XsSelfTestResult XsSelfTestResult
XsResetMethod
Orientation reset type.
size_t XsSize
XsSize must be unsigned number!
@ XDS_WaitingForRecordingStart
A class to store version information.
bool setNoRotation(uint16_t duration)
Set the no rotation period to duration.
bool messageLooksSane(const XsMessage &msg) const override
Checks for the sanity of a message.
virtual int getBaseFrequency(XsDataIdentifier dataType=XDI_None) const
Returns the base update rate (Hz) corresponding to the dataType. Returns 0 if no update rate is avail...
uint32_t supportedStatusFlags() const override
Returns a bitmask with all the status flags supported by this device.
XsFilterProfileArray m_hardwareFilterProfiles
A vector of hardware filter profiles.
Structure for storing a single message.
bool requestData()
Request data from the motion tracker.
Contains an Xsens device ID and provides operations for determining the type of device.
struct XsIntArray XsIntArray
@ XMID_ReqAvailableFilterProfiles
Request the available filter profiles.
virtual bool readDeviceConfiguration()
virtual bool resetLogFileReadPosition()
Set the read position of the open log file to the start of the file.
virtual void clearDataCache()
virtual bool scheduleOrientationReset(XsResetMethod method)
@ XRM_DefaultHeading
Revert to default behaviour for heading, undoes XRM_Heading.
uint32_t usToSyncTicks(uint32_t us) const
Convert microseconds to mt sync ticks.
Device information for MT devices in an XsDeviceConfiguration.
#define XS_LEN_FILTERPROFILELABEL
bool isMotionTracker() const override
bool setGnssReceiverSettings(const XsIntArray &gnssReceiverSettings) override
Sets some GNSS receiver settings.
XsErrorMode
Error modes for use in XsDevice::setErrorMode.
uint16_t stringOutputType() const override
Returns the string output type.
@ XMID_ReqGnssReceiverSettings
virtual void writeMessageToLogFile(const XsMessage &message)
@ XMID_ReqOutputSkipFactor
@ XFPK_Heading
Indicates a heading profile.
@ XRM_StoreAlignmentMatrix
Store the current object alignment matrix to persistent memory.
XsMessage m_emtsBlob
An EMTS blob from device.
@ XDI_OrientationGroup
Group for orientation related outputs.
double gyroscopeRange() const
void setInitialized(bool initialized)
Set the initialized state to initialized.
@ XMID_ReqHardwareVersion
bool doTransaction(const XsMessage &snd) const
@ XFPK_Base
Indicates a base profile.
virtual bool scheduleOrientationReset(XsResetMethod method)
XsVector initialPositionLLA() const override
XBR_Invalid
Not a valid baud rate.
XsUbloxGnssPlatform ubloxGnssPlatform() const override
Returns the device GNSS platform for u-blox GNSS receivers.
#define XS_BID_INVALID
An invalid bus identifier.
@ XMID_ReqFilterProfile
Request the current filter profile.
A 0-terminated managed string of characters.
static int calcFrequency(int baseFrequency, uint16_t skipFactor)
Calculates the frequency.
int locationId() const
Get the location ID of the device.
@ XRM_DefaultAlignment
Revert to default behaviour for heading and inclination, undoes any reset.
bool reinitialize()
Reinitialize the XsDevice.
XsOutputConfigurationArray outputConfiguration() const override
Returns the currently configured output of the device.
bool resetLogFileReadPosition() override
Set the read position of the open log file to the start of the file.
XsDeviceOptionFlag
Used to enable or disable some device options.
bool setUbloxGnssPlatform(XsUbloxGnssPlatform ubloxGnssPlatform) override
Set the device GNSS platform for u-blox GNSS receivers.
XsBaudRate serialBaudRate() const override
The baud rate configured for cabled connection.
@ XMID_SetGnssReceiverSettings
bool storeFilterState() override
Store orientation filter state in the device.