19 #if MRPT_HAS_xSENS_MT4 32 #include <xsens/enumerateusbdevices.h> 33 #include <xsens/int_xsdatapacket.h> 34 #include <xsens/legacydatapacket.h> 35 #include <xsens/protocolhandler.h> 36 #include <xsens/serialinterface.h> 37 #include <xsens/streaminterface.h> 38 #include <xsens/usbinterface.h> 39 #include <xsens/xsbytearray.h> 40 #include <xsens/xsdatapacket.h> 41 #include <xsens/xsdeviceid.h> 42 #include <xsens/xsmessagearray.h> 43 #include <xsens/xsoutputconfigurationarray.h> 44 #include <xsens/xsoutputmode.h> 45 #include <xsens/xsoutputsettings.h> 46 #include <xsens/xsportinfo.h> 47 #include <xsens/xsportinfoarray.h> 48 #include <xsens/xsresultvalue.h> 49 #include <xsens/xsstatusflag.h> 50 #include <xsens/xstime.h> 55 DeviceClass() =
default;
56 ~DeviceClass() =
default;
62 bool openPort(
const XsPortInfo& portInfo)
65 m_streamInterface = std::make_unique<UsbInterface>();
67 m_streamInterface = std::make_unique<SerialInterface>();
69 if (m_streamInterface->open(portInfo) != XRV_OK)
return false;
77 if (m_streamInterface) m_streamInterface->close();
89 XsResultValue readDataToBuffer(XsByteArray& raw)
92 const int maxSz = 8192;
93 XsResultValue res = m_streamInterface->readData(maxSz, raw);
94 if (raw.size())
return XRV_OK;
108 XsResultValue processBufferedData(
109 XsByteArray& rawIn, XsMessageArray& messages)
111 ProtocolHandler protocol;
113 if (rawIn.size()) m_dataBuffer.append(rawIn);
121 m_dataBuffer.data() + popped, m_dataBuffer.size() - popped);
123 MessageLocation location = protocol.findMessage(message, raw);
125 if (location.isValid())
128 popped += location.m_size + location.m_startPos;
129 messages.push_back(message);
133 if (popped) m_dataBuffer.pop_front(popped);
135 if (messages.empty())
return XRV_TIMEOUTNODATA;
147 bool waitForMessage(XsXbusMessageId xmid, XsMessage& rcv)
151 bool foundAck =
false;
154 readDataToBuffer(
data);
155 processBufferedData(
data, msgs);
156 for (XsMessageArray::iterator it = msgs.begin(); it != msgs.end();
158 if ((*it).getMessageId() == xmid)
171 bool writeMessage(
const XsMessage& msg)
174 if (ProtocolHandler::composeMessage(raw, msg) < 0)
return false;
176 return (m_streamInterface->writeData(raw) == XRV_OK);
184 XsMessage snd(XMID_GotoConfig, 0), rcv;
187 return waitForMessage(XMID_GotoConfigAck, rcv);
193 bool gotoMeasurement()
195 XsMessage snd(XMID_GotoMeasurement, 0), rcv;
198 return waitForMessage(XMID_GotoMeasurementAck, rcv);
204 XsString getProductCode()
206 XsMessage snd(XMID_ReqProductCode, 0), rcv;
209 if (waitForMessage(XMID_ProductCode, rcv))
211 const char* pc = (
const char*)rcv.getDataBuffer(0);
212 std::string result(pc ? pc :
"", rcv.getDataSize());
213 std::string::size_type thingy = result.find(
" ");
216 result.begin() + thingy, result.end());
217 return XsString(result);
227 XsDeviceId getDeviceId()
229 XsMessage snd(XMID_ReqDid, 0), rcv;
232 if (waitForMessage(XMID_DeviceId, rcv))
234 return rcv.getDataLong();
246 const XsOutputMode& outputMode,
const XsOutputSettings& outputSettings)
248 XsMessage sndOM(XMID_SetOutputMode), sndOS(XMID_SetOutputSettings), rcv;
251 sndOM.setDataShort((uint16_t)outputMode);
253 if (!waitForMessage(XMID_SetOutputModeAck, rcv))
return false;
255 XsMessage snd(XMID_SetOutputSettings);
257 snd.setDataLong((uint32_t)outputSettings);
259 if (!waitForMessage(XMID_SetOutputSettingsAck, rcv))
return false;
269 bool setOutputConfiguration(XsOutputConfigurationArray& config)
271 XsMessage snd(XMID_SetOutputConfiguration, 4), rcv;
272 if (config.size() == 0)
274 snd.setDataShort((uint16_t)XDI_None, 0);
275 snd.setDataShort(0, 2);
279 for (XsSize i = 0; i < (XsSize)config.size(); ++i)
281 snd.setDataShort((uint16_t)config[i].m_dataIdentifier, i * 4);
282 snd.setDataShort(config[i].m_frequency, i * 4 + 2);
287 return waitForMessage(XMID_SetOutputConfigurationAck, rcv);
291 std::unique_ptr<StreamInterface> m_streamInterface;
292 XsByteArray m_dataBuffer;
297 #define my_xsens_device (*static_cast<DeviceClass*>(m_dev_ptr)) 298 #define my_xsens_devid (*static_cast<XsDeviceId*>(m_devid_ptr)) 301 #if MRPT_HAS_xSENS_MT4 304 #if defined(_MSC_VER) 305 #pragma comment(lib, "SetupAPI.lib") 306 #pragma comment(lib, "WinUsb.lib") 309 #endif // MRPT_HAS_xSENS_MT4 320 CIMUXSens_MT4::CIMUXSens_MT4() : m_portname(), m_timeStartTT(), m_sensorPose()
325 #if MRPT_HAS_xSENS_MT4 330 "MRPT has been compiled with 'BUILD_XSENS_MT4'=OFF, so this class " 340 #if MRPT_HAS_xSENS_MT4 342 delete static_cast<DeviceClass*
>(
m_dev_ptr);
355 #if MRPT_HAS_xSENS_MT4 358 std::this_thread::sleep_for(200ms);
369 for (XsMessageArray::iterator it = msgs.begin(); it != msgs.end(); ++it)
373 if ((*it).getMessageId() == XMID_MtData)
375 LegacyDataPacket lpacket(1,
false);
377 lpacket.setMessage((*it));
378 lpacket.setXbusSystem(
false,
false);
380 lpacket.setDataFormat(
382 XOS_OrientationMode_Euler | XOS_Timestamp_PacketCounter |
383 XOS_CalibratedMode_All ,
385 XsDataPacket_assignFromXsLegacyDataPacket(&packet, &lpacket, 0);
387 else if ((*it).getMessageId() == XMID_MtData2)
389 packet.setMessage((*it));
398 if (packet.containsOrientation())
400 XsEuler euler = packet.orientationEuler();
402 obs->dataIsPresent[
IMU_YAW] =
true;
406 obs->dataIsPresent[
IMU_ROLL] =
true;
408 XsQuaternion quat = packet.orientationQuaternion();
419 if (packet.containsCalibratedAcceleration())
421 XsVector acc_data = packet.calibratedAcceleration();
422 obs->rawMeasurements[
IMU_X_ACC] = acc_data[0];
424 obs->rawMeasurements[
IMU_Y_ACC] = acc_data[1];
426 obs->rawMeasurements[
IMU_Z_ACC] = acc_data[2];
430 if (packet.containsCalibratedGyroscopeData())
432 XsVector gyr_data = packet.calibratedGyroscopeData();
441 if (packet.containsCalibratedMagneticField())
443 XsVector mag_data = packet.calibratedMagneticField();
444 obs->rawMeasurements[
IMU_MAG_X] = mag_data[0];
446 obs->rawMeasurements[
IMU_MAG_Y] = mag_data[1];
448 obs->rawMeasurements[
IMU_MAG_Z] = mag_data[2];
452 if (packet.containsVelocity())
454 XsVector vel_data = packet.velocity();
455 obs->rawMeasurements[
IMU_X_VEL] = vel_data[0];
457 obs->rawMeasurements[
IMU_Y_VEL] = vel_data[1];
459 obs->rawMeasurements[
IMU_Z_VEL] = vel_data[2];
463 if (packet.containsTemperature())
469 if (packet.containsAltitude())
476 if (packet.containsSampleTime64())
478 const uint64_t nowUI = packet.sampleTime64();
489 obs->timestamp =
m_timeStartTT + std::chrono::milliseconds(AtUI);
491 else if (packet.containsUtcTime())
493 XsUtcTime utc = packet.utcTime();
499 parts.
year = utc.m_year;
500 parts.
month = utc.m_month;
501 parts.
day = utc.m_day;
502 parts.
hour = utc.m_hour;
503 parts.
minute = utc.m_minute;
504 parts.
second = utc.m_second + (utc.m_nano * 1000000000.0);
516 if (packet.containsLatitudeLongitude())
518 XsVector lla_data = packet.latitudeLongitude();
526 if (packet.containsStatus() && packet.status() & XSF_GpsValid)
531 if (packet.containsUtcTime())
533 XsUtcTime utc = packet.utcTime();
536 rGPS.
UTCTime.
sec = utc.m_second + (utc.m_nano * 1000000.0);
541 ((obs->timestamp.time_since_epoch().count() /
542 (60 * 60 * ((uint64_t)1000000 / 100))) %
545 ((obs->timestamp.time_since_epoch().count() /
546 (60 * ((uint64_t)1000000 / 100))) %
549 obs->timestamp.time_since_epoch().count() /
554 if (packet.containsVelocity())
556 XsVector vel_data = packet.velocity();
559 sqrt(vel_data[0] * vel_data[0] + vel_data[1] * vel_data[1]);
567 obsGPS->setMsg(rGPSs);
568 obsGPS->timestamp = obs->timestamp;
569 obsGPS->originalReceivedTimestamp = obs->timestamp;
570 obsGPS->has_satellite_timestamp =
false;
580 "MRPT has been compiled with 'BUILD_XSENS_MT4'=OFF, so this class " 590 #if MRPT_HAS_xSENS_MT4 596 XsPortInfoArray portInfoArray;
601 cout <<
"[CIMUXSens_MT4] Scanning for USB devices...\n";
602 xsEnumerateUsbDevices(portInfoArray);
604 if (portInfoArray.empty())
606 "CIMUXSens_MT4: No 'portname' was specified and no XSens " 607 "device was found after scanning the system!");
610 cout <<
"[CIMUXSens_MT4] Found " << portInfoArray.size()
611 <<
" devices. Opening the first one.\n";
618 cout <<
"[CIMUXSens_MT4] Using user-supplied portname '" 620 portInfoArray.push_back(portInfo);
624 XsPortInfo mtPort = portInfoArray.at(0);
627 cout <<
"[CIMUXSens_MT4] Opening port " 628 << mtPort.portName().toStdString() << std::endl;
631 throw std::runtime_error(
"Could not open port. Aborting.");
635 cout <<
"[CIMUXSens_MT4] Putting device into configuration " 640 throw std::runtime_error(
641 "Could not put device into configuration mode. Aborting.");
649 if (!mtPort.deviceId().isMtix() && !mtPort.deviceId().isMtMk4())
651 throw std::runtime_error(
652 "No MTi / MTx / MTmk4 device found. Aborting.");
654 cout <<
"[CIMUXSens_MT4] Found a device with id: " 655 << mtPort.deviceId().toString().toStdString()
656 <<
" @ port: " << mtPort.portName().toStdString()
657 <<
", baudrate: " << mtPort.baudrate() << std::endl;
661 cout <<
"[CIMUXSens_MT4] Device: " 667 cout <<
"[CIMUXSens_MT4] Configuring the device..." << std::endl;
668 if (mtPort.deviceId().isMtix())
670 XsOutputMode outputMode =
672 XsOutputSettings outputSettings =
673 XOS_OrientationMode_Euler | XOS_Timestamp_PacketCounter |
674 XOS_CalibratedMode_All;
680 throw std::runtime_error(
681 "Could not configure MT device. Aborting.");
683 else if (mtPort.deviceId().isMtMk4())
685 XsOutputConfigurationArray configArray;
686 configArray.push_back(
688 configArray.push_back(
689 XsOutputConfiguration(XDI_SampleTimeFine,
m_sampleFreq));
690 configArray.push_back(
691 XsOutputConfiguration(XDI_SampleTimeCoarse,
m_sampleFreq));
692 configArray.push_back(
694 configArray.push_back(
696 configArray.push_back(
698 configArray.push_back(
700 configArray.push_back(
701 XsOutputConfiguration(XDI_MagneticField,
m_sampleFreq));
702 configArray.push_back(
705 configArray.push_back(
707 configArray.push_back(
709 configArray.push_back(
711 configArray.push_back(
712 XsOutputConfiguration(XDI_AltitudeEllipsoid,
m_sampleFreq));
715 throw std::runtime_error(
716 "Could not configure MTmk4 device. Aborting.");
720 throw std::runtime_error(
721 "Unknown device while configuring. Aborting.");
726 cout <<
"[CIMUXSens_MT4] Putting device into measurement mode..." 729 throw std::runtime_error(
730 "Could not put device into measurement mode. Aborting.");
734 catch (std::exception&)
737 std::cerr <<
"Error Could not initialize the device" << std::endl;
743 "MRPT has been compiled with 'BUILD_XSENS_MT4'=OFF, so this class " 753 const std::string& iniSection)
756 configSource.
read_float(iniSection,
"pose_x", 0,
false),
757 configSource.
read_float(iniSection,
"pose_y", 0,
false),
758 configSource.
read_float(iniSection,
"pose_z", 0,
false),
void initialize() override
Turns on the xSens device and configure it for getting orientation data.
mrpt::system::TTimeStamp m_timeStartTT
content_t fields
Message content, accesible by individual fields.
double longitude_degrees
The measured longitude, in degrees (East:+ , West:-)
void appendObservation(const mrpt::serialization::CSerializable::Ptr &obj)
Like appendObservations() but for just one observation.
std::string read_string(const std::string §ion, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
mrpt::poses::CPose3D m_sensorPose
#define THROW_EXCEPTION(msg)
void doProcess() override
This method will be invoked at a minimum rate of "process_rate" (Hz)
std::string m_sensorLabel
See CGenericSensor.
orientation pitch absolute value (global/navigation frame) (rad)
mrpt::system::TTimeStamp buildTimestampFromParts(const mrpt::system::TTimeParts &p)
Builds a timestamp from the parts (Parts are in UTC)
uint8_t day_of_week
Seconds (0.0000-59.9999)
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Contains classes for various device interfaces.
temperature (degrees Celsius)
float read_float(const std::string §ion, const std::string &name, float defaultValue, bool failIfNotFound=false) const
x magnetic field value (local/vehicle frame) (gauss)
y-axis acceleration (local/vehicle frame) (m/sec2)
Orientation Quaternion X (global/navigation frame)
z-axis acceleration (local/vehicle frame) (m/sec2)
x-axis velocity (global/navigation frame) (m/sec)
int8_t validity_char
This will be: 'A'=OK or 'V'=void.
UTC_time UTCTime
The GPS sensor measured timestamp (in UTC time)
std::string m_portname
The USB or COM port name (if blank -> autodetect)
int m_port_bauds
Baudrate, only for COM ports.
int read_int(const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const
pitch angular velocity (local/vehicle frame) (rad/sec)
int daylight_saving
Day of week (1:Sunday, 7:Saturday)
This class allows loading and storing values and vectors of different types from a configuration text...
void loadConfig_sensorSpecific(const mrpt::config::CConfigFileBase &configSource, const std::string &iniSection) override
See the class documentation at the top for expected parameters.
constexpr double DEG2RAD(const double x)
Degrees to radians.
The parts of a date/time (it's like the standard 'tm' but with fractions of seconds).
This namespace contains representation of robot actions and observations.
Orientation Quaternion Y (global/navigation frame)
~CIMUXSens_MT4() override
Destructor.
Orientation Quaternion Z (global/navigation frame)
z magnetic field value (local/vehicle frame) (gauss)
Orientation Quaternion W (global/navigation frame)
#define IMPLEMENTS_GENERIC_SENSOR(class_name, NameSpace)
This must be inserted in all CGenericSensor classes implementation files:
double second
Minute (0-59)
y magnetic field value (local/vehicle frame) (gauss)
double speed_knots
Measured speed (in knots)
uint8_t minute
Hour (0-23)
double direction_degrees
Measured speed direction (in degrees)
void setFromValues(const double x0, const double y0, const double z0, const double yaw=0, const double pitch=0, const double roll=0)
Set the pose from a 3D position (meters) and yaw/pitch/roll angles (radians) - This method recomputes...
A class for interfacing XSens 4th generation Inertial Measuring Units (IMUs): MTi 10-series...
double latitude_degrees
The measured latitude, in degrees (North:+ , South:-)
orientation yaw absolute value (global/navigation frame) (rad)
y-axis velocity (global/navigation frame) (m/sec)
orientation roll absolute value (global/navigation frame) (rad)
yaw angular velocity (local/vehicle frame) (rad/sec)
roll angular velocity (local/vehicle frame) (rad/sec)
x-axis acceleration (local/vehicle frame) (m/sec2)
z-axis velocity (global/navigation frame) (m/sec)
altitude from an altimeter (meters)
static struct FontData data