Skip to content

Commit

Permalink
Public release MSCL 57.2.2
Browse files Browse the repository at this point in the history
  • Loading branch information
mgill committed Jul 29, 2020
1 parent d0f0b9d commit 396a3c9
Show file tree
Hide file tree
Showing 79 changed files with 7,055 additions and 1,000 deletions.
93 changes: 93 additions & 0 deletions CHANGELOG.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,99 @@ RENAMED - A function/class has been renamed.
REMOVED - A function/class has been removed.
======================================================================================================

57.2.2 - 2020-07-28
- Add additional options to following enums for new product support:
- InertialTypes::GnssFixType
- InertialTypes::FilterState
- InertialTypes::FilterStatus_Running

57.2.1 - 2020-07-27
- Add support for MIP Commands:
- Commanded Zero-Velocity Update (0x0D, 0x22)
- Commanded Zero-Angular Rate Update (0x0D, 0x23)

57.2.0 - 2020-07-21
- Update GQ7 and RTK model numbers:
- 3DM-GQ7: 6284
- RTK: 6285
- Add support for MIP Commands:
- Receiver Info (0x0E, 0x01)
- Generic Poll Data (0x0C,0x0D)
- Sensor to Vehicle Frame Transformation Euler (0x0C,0x31)
- Sensor to Vehicle Frame Transformation Quaternion (0x0C,0x32)
- Sensor to Vehicle Frame Transformation DCM (0x0C,0x33)
- Get config command bytes for Multi-Antenna Offset (0x0D,0x54) based on reported receivers
- Update enum definitions:
- AidingMeasurementSource
- HeadingAlignmentOption (add HeadingAlignmentMethod view)
- PpsInputOutput

57.1.4 - 2020-07-17
- MipCommand: allow function selector to be included for undefined commands despite being reported as 'not supported'

57.1.3 - 2020-07-15
- Fixed data response parsing for inertial commands:
- Accel Bias (0x0C,0x37)
- Gyro Bias (0x0C,0x38)
- Capture Gyro Bias (0x0C,0x39)
- Magnetometer Hard Iron Offset (0x0C,0x3A)
- updated inertial command Advanced Low-Pass Filter Settings (0x0C,0x50) to send 0 for cutoff frequency when automatic specified

57.1.2 - 2020-07-14
- Added response descriptor parameter to GenericMipCommand::Response constructor

57.1.1 - 2020-07-10
- Added support for MIP Commands:
- Factory Streaming (0x0C,0x10): InertialNode::setFactoryStreamingChannels()
- PPS Source (0x0C,0x28): InertialNode::get/setPpsSource()
- PPS Output (0x0C,0x29): InertialNode::get/setPpsOutput()

57.1.0 - 2020-06-30
- Added support for existing GNSS MIP data fields for new GNSS data sets (0x91-95)
- Fixed bug that prevented function selector byte being included in MIP packet when using MipCommand class for undefined command IDs

57.0.0 - 2020-06-29
- CHANGED constructor MipNodeInfo(MipDeviceInfo, vector<uint16>, mscl::SampleRates, mscl::SampleRates, mscl::SampleRates) to MipNodeInfo(MipDeviceInfo, vector<uint16>, map<mscl::MipTypes::DataClass, mscl::SampleRates>) to better support more possible supported data classes
- Added data set descriptors for MIP data sets GNSS 1-5 (0x91-95) to MipTypes::DataClass and DescriptorSet
- Add MipNodeFeatures::useLegacyIdsForEnableDataStream() to support parameter definition changes in the Data Stream Control command (0x0C, 0x11)

56.1.2 - 2020-06-19
- Add support for new generic Message Format (0x0C, 0x0F) and Get Base Rate (0x0C, 0x0E) MIP commands
- Add function SampleRate::FromInertialRateDecimationInfo() to build a SampleRate object from base rate and rate decimation values

56.1.1 - 2020-06-19
- Added FilterInitializationValues::autoInitialize to support command definition change

56.0.1 - 2020-06-17
- Added support for RTK device type
- Added support for Get RTK Device Status Flags (0x0F,0x01)

56.0.0 - 2020-05-28
- RENAMED InertialNode::get/setSensorToVehicleTransformation() to get/setSensorToVehicleRotation_eulerAngles() for accuracy
- RENAMED MipTypes::Command::CMD_EF_SENS_VEHIC_FRAME_TRANS to CMD_EF_SENS_VEHIC_FRAME_ROTATION_EULER
- Added support for commands:
- Sensor to Vehicle Frame Rotation DCM (0x0D,0x4E)
- Sensor to Vehicle Frame Rotation Quaternion (0x0D,0x4F)
- Added class Quaternion (extends Matrix)

55.0.4 - 2020-05-21
- Added InertialNode::saveSettingsAsStartup that accepts a list of commmand IDs and saves only those specified

55.0.3 - 2020-05-21
- Added support for fields:
- GNSS RTK Corrections Status (0x81,0x31)
- GPS Ionospheric Correction (0x81,0x71)
- GNSS Ionospheric Correction (0x81,0x73)
- GNSS Clock Info 2 (0x81,0x10)
- GNSS GPS Leap Seconds (0x81,0x11)

55.0.2 - 2020-05-14
- Added support for fields:
- AHRS Data: Raw Pressure (0x80, 0x16)
- AHRS Data: Temperature Abs (0x80, 0x14)
- Filter Data: Mag Bias (0x82, 0x1A)
- Filter Data: Mag Bias Uncertainty (0x82, 0x1B)

55.0.1 - 2020-04-3
- Added asMap function for DeviceStatusData returned by the DeviceStatus command
- returns a map of DeviceStatusValues and string values representing the device status
Expand Down
2 changes: 2 additions & 0 deletions MSCL/Jamfile
Original file line number Diff line number Diff line change
Expand Up @@ -116,6 +116,8 @@ alias msclSrcs
[ glob source/mscl/MicroStrain/Inertial/Packets/*.cpp ]
[ glob source/mscl/MicroStrain/Displacement/*.cpp ]
[ glob source/mscl/MicroStrain/Displacement/Commands/*.cpp ]
[ glob source/mscl/MicroStrain/RTK/*.cpp ]
[ glob source/mscl/MicroStrain/RTK/Commands/*.cpp ]
[ glob source/mscl/MicroStrain/MIP/*.cpp ]
[ glob source/mscl/MicroStrain/MIP/Commands/*.cpp ]
[ glob source/mscl/MicroStrain/MIP/Packets/*.cpp ]
Expand Down
7 changes: 7 additions & 0 deletions MSCL/MSCL.vcxproj
Original file line number Diff line number Diff line change
Expand Up @@ -781,6 +781,9 @@
<ClInclude Include="source\mscl\MicroStrain\MIP\Packets\MipPacket.h" />
<ClInclude Include="source\mscl\MicroStrain\MIP\Packets\MipPacketBuilder.h" />
<ClInclude Include="source\mscl\MicroStrain\MIP\Packets\MipPacketCollector.h" />
<ClInclude Include="source\mscl\MicroStrain\RTK\Commands\DeviceStatusFlags.h" />
<ClInclude Include="source\mscl\MicroStrain\RTK\RTKModels.h" />
<ClInclude Include="source\mscl\MicroStrain\RTK\RTKNode.h" />
<ClInclude Include="source\mscl\MicroStrain\Wireless\ArmedDataloggingNetwork.h" />
<ClInclude Include="source\mscl\MicroStrain\Wireless\BaseStationAnalogPair.h" />
<ClInclude Include="source\mscl\MicroStrain\Wireless\BaseStationButton.h" />
Expand Down Expand Up @@ -1099,6 +1102,9 @@
<ClCompile Include="source\mscl\MicroStrain\MIP\Packets\MipPacket.cpp" />
<ClCompile Include="source\mscl\MicroStrain\MIP\Packets\MipPacketBuilder.cpp" />
<ClCompile Include="source\mscl\MicroStrain\MIP\Packets\MipPacketCollector.cpp" />
<ClCompile Include="source\mscl\MicroStrain\RTK\Commands\DeviceStatusFlags.cpp" />
<ClCompile Include="source\mscl\MicroStrain\RTK\RTKModels.cpp" />
<ClCompile Include="source\mscl\MicroStrain\RTK\RTKNode.cpp" />
<ClCompile Include="source\mscl\MicroStrain\Wireless\ArmedDataloggingNetwork.cpp" />
<ClCompile Include="source\mscl\MicroStrain\Wireless\BaseStationAnalogPair.cpp" />
<ClCompile Include="source\mscl\MicroStrain\Wireless\BaseStationButton.cpp" />
Expand Down Expand Up @@ -1357,6 +1363,7 @@
<ClCompile Include="source\mscl\Utils.cpp" />
</ItemGroup>
<ItemGroup>
<None Include="ClassDiagram.cd" />
<None Include="source\mscl\Wrapper\MSCL_Exceptions.i" />
<None Include="source\mscl\Wrapper\MSCL_Main_Interface.i" />
</ItemGroup>
Expand Down
25 changes: 25 additions & 0 deletions MSCL/MSCL.vcxproj.filters
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,12 @@
<Filter Include="MicroStrain\Displacement\Commands">
<UniqueIdentifier>{2d816ebe-dc87-4cd4-b97f-9e952ba15164}</UniqueIdentifier>
</Filter>
<Filter Include="MicroStrain\RTK">
<UniqueIdentifier>{4160275e-7fa9-4c22-8578-607d82e2b2bf}</UniqueIdentifier>
</Filter>
<Filter Include="MicroStrain\RTK\Commands">
<UniqueIdentifier>{a49d32a6-b691-45ec-b639-26ffa719c426}</UniqueIdentifier>
</Filter>
</ItemGroup>
<ItemGroup>
<ClInclude Include="source\mscl\Exceptions.h" />
Expand Down Expand Up @@ -980,6 +986,15 @@
<ClInclude Include="source\mscl\MicroStrain\Wireless\Features\NodeFeatures_ptlink200.h">
<Filter>MicroStrain\Wireless\Features\Nodes</Filter>
</ClInclude>
<ClInclude Include="source\mscl\MicroStrain\RTK\RTKNode.h">
<Filter>MicroStrain\RTK</Filter>
</ClInclude>
<ClInclude Include="source\mscl\MicroStrain\RTK\RTKModels.h">
<Filter>MicroStrain\RTK</Filter>
</ClInclude>
<ClInclude Include="source\mscl\MicroStrain\RTK\Commands\DeviceStatusFlags.h">
<Filter>MicroStrain\RTK\Commands</Filter>
</ClInclude>
</ItemGroup>
<ItemGroup>
<ClCompile Include="source\mscl\MicroStrain\ByteStream.cpp">
Expand Down Expand Up @@ -1857,6 +1872,15 @@
<ClCompile Include="source\mscl\MicroStrain\Wireless\Features\NodeFeatures_ptlink200.cpp">
<Filter>MicroStrain\Wireless\Features\Nodes</Filter>
</ClCompile>
<ClCompile Include="source\mscl\MicroStrain\RTK\RTKNode.cpp">
<Filter>MicroStrain\RTK</Filter>
</ClCompile>
<ClCompile Include="source\mscl\MicroStrain\RTK\RTKModels.cpp">
<Filter>MicroStrain\RTK</Filter>
</ClCompile>
<ClCompile Include="source\mscl\MicroStrain\RTK\Commands\DeviceStatusFlags.cpp">
<Filter>MicroStrain\RTK\Commands</Filter>
</ClCompile>
</ItemGroup>
<ItemGroup>
<None Include="source\mscl\Wrapper\MSCL_Exceptions.i">
Expand All @@ -1865,5 +1889,6 @@
<None Include="source\mscl\Wrapper\MSCL_Main_Interface.i">
<Filter>_Wrapper</Filter>
</None>
<None Include="ClassDiagram.cd" />
</ItemGroup>
</Project>
6 changes: 3 additions & 3 deletions MSCL/source/mscl/LibVersion.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,9 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License.

#ifndef SWIG
//update with each release
#define MSCL_MAJOR 55
#define MSCL_MINOR 0
#define MSCL_PATCH 1
#define MSCL_MAJOR 57
#define MSCL_MINOR 2
#define MSCL_PATCH 2
#endif

namespace mscl
Expand Down
5 changes: 4 additions & 1 deletion MSCL/source/mscl/MicroStrain/Inertial/Commands/AccelBias.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,10 @@ namespace mscl
GeometricVector AccelBias::getResponseData(const GenericMipCmdResponse& response)
{
DataBuffer dataBuffer(response.data());
GeometricVector returnData { dataBuffer.read_float(), dataBuffer.read_float(), dataBuffer.read_float() };
GeometricVector returnData;
returnData.x(dataBuffer.read_float());
returnData.y(dataBuffer.read_float());
returnData.z(dataBuffer.read_float());
return returnData;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,9 +57,12 @@ namespace mscl
if (m_functionSelector == MipTypes::USE_NEW_SETTINGS)
{
MipTypes::EnableSetting applyLowPassFilter = m_data.applyLowPassFilter ? MipTypes::ENABLED : MipTypes::DISABLED;
uint16 freq = m_data.manualFilterBandwidthConfig == AdvancedLowPassFilterData::USER_SPECIFIED_CUTOFF_FREQ ? m_data.cutoffFrequency : 0x0000;

byteCommand.append_uint8(static_cast<uint8>(applyLowPassFilter));
byteCommand.append_uint8(static_cast<uint8>(m_data.manualFilterBandwidthConfig));
byteCommand.append_uint16(static_cast<uint16>(m_data.cutoffFrequency));
byteCommand.append_uint16(freq);
byteCommand.append_uint8(0x00);
}
return GenericMipCommand::buildCommand(commandType(), byteCommand.data()); ;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,10 @@ namespace mscl
GeometricVector CaptureGyroBias::getResponseData(const GenericMipCmdResponse& response)
{
DataBuffer dataBuffer(response.data());
GeometricVector returnData{ dataBuffer.read_float(), dataBuffer.read_float(), dataBuffer.read_float() };
GeometricVector returnData;
returnData.x(dataBuffer.read_float());
returnData.y(dataBuffer.read_float());
returnData.z(dataBuffer.read_float());
return returnData;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -392,6 +392,46 @@ namespace mscl
}
//==========================================================================================

//==========================================================================================
//Commanded Velocity Zupt
ByteStream CmdedVelZupt::buildCommand_get()
{
//container to hold the command's field data
ByteStream fieldData;

//add the command selector byte
fieldData.append_uint8(static_cast<uint8>(MipTypes::READ_BACK_CURRENT_SETTINGS));

//build and return the command bytes
return GenericMipCommand::buildCommand(CMD_ID, fieldData.data());
}

CmdedVelZupt::Response::Response(std::weak_ptr<ResponseCollector> collector, bool dataResponse):
GenericMipCommand::Response(MipTypes::CMD_EF_CMDED_ZERO_VEL_UPDATE, collector, true, false, "Commanded Zero Velocity Update")
{
}
//==========================================================================================

//==========================================================================================
//Commanded Angular Zupt
ByteStream CmdedAngularZupt::buildCommand_get()
{
//container to hold the command's field data
ByteStream fieldData;

//add the command selector byte
fieldData.append_uint8(static_cast<uint8>(MipTypes::READ_BACK_CURRENT_SETTINGS));

//build and return the command bytes
return GenericMipCommand::buildCommand(CMD_ID, fieldData.data());
}

CmdedAngularZupt::Response::Response(std::weak_ptr<ResponseCollector> collector, bool dataResponse) :
GenericMipCommand::Response(MipTypes::CMD_EF_CMDED_ZERO_ANG_RATE_UPDATE, collector, true, false, "Commanded Zero Angular Rate Update")
{
}
//==========================================================================================

//==========================================================================================
//Sensor to Vehicle Frame Transformation
ByteStream SensorToVehicFrameTrans::buildCommand_get()
Expand Down Expand Up @@ -424,7 +464,7 @@ namespace mscl
}

SensorToVehicFrameTrans::Response::Response(std::weak_ptr<ResponseCollector> collector, bool dataResponse):
GenericMipCommand::Response(MipTypes::CMD_EF_SENS_VEHIC_FRAME_TRANS, collector, true, dataResponse, "Sensor to Vehicle Frame Transformation")
GenericMipCommand::Response(MipTypes::CMD_EF_SENS_VEHIC_FRAME_ROTATION_EULER, collector, true, dataResponse, "Sensor to Vehicle Frame Transformation")
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -441,15 +441,76 @@ namespace mscl
};
};

//Class: CmdedVelZupt
// Contains the logic for the "Commanded Zero Velocity Update" command
class CmdedVelZupt
{
public:
//Constants: Packet Bytes
// CMD_ID - CMD_EF_CMDED_ZERO_VEL_UPDATE - The <MipTypes::Command> for this command
// FIELD_DATA_BYTE - 0xF1 - The Data Field Descriptor byte
static const MipTypes::Command CMD_ID = MipTypes::CMD_EF_CMDED_ZERO_VEL_UPDATE;
static const uint8 FIELD_DATA_BYTE = 0xF1;

private:
CmdedVelZupt() = delete;

public:
//Function: buildCommand_get
// Builds the bytes for the "get" command.
static ByteStream buildCommand_get();

class Response : public GenericMipCommand::Response
{
protected:
virtual MipTypes::Command commandId() const { return CMD_ID; }
virtual uint8 fieldDataByte() const { return FIELD_DATA_BYTE; }

public:
Response(std::weak_ptr<ResponseCollector> collector, bool dataResponse);
};
};


//Class: CmdedAngularZupt
// Contains the logic for the "Commanded Zero Angular Rate Update" command
class CmdedAngularZupt
{
public:
//Constants: Packet Bytes
// CMD_ID - CMD_EF_CMDED_ZERO_ANG_RATE_UPDATE - The <MipTypes::Command> for this command
// FIELD_DATA_BYTE - 0xF1 - The Data Field Descriptor byte
static const MipTypes::Command CMD_ID = MipTypes::CMD_EF_CMDED_ZERO_ANG_RATE_UPDATE;
static const uint8 FIELD_DATA_BYTE = 0xF1;

private:
CmdedAngularZupt() = delete;

public:
//Function: buildCommand_get
// Builds the bytes for the "get" command.
static ByteStream buildCommand_get();

class Response : public GenericMipCommand::Response
{
protected:
virtual MipTypes::Command commandId() const { return CMD_ID; }
virtual uint8 fieldDataByte() const { return FIELD_DATA_BYTE; }

public:
Response(std::weak_ptr<ResponseCollector> collector, bool dataResponse);
};
};

//Class: SensorToVehicFrameTrans
// Contains the logic for the "Sensor to Vehicle Frame Transformation" command
class SensorToVehicFrameTrans
{
public:
//Constants: Packet Bytes
// CMD_ID - CMD_EF_SENS_VEHIC_FRAME_TRANS - The <MipTypes::Command> for this command
// FIELD_DATA_BYTE - 0x81 - The Data Field Descriptor byte
static const MipTypes::Command CMD_ID = MipTypes::CMD_EF_SENS_VEHIC_FRAME_TRANS;
// CMD_ID - CMD_EF_SENS_VEHIC_FRAME_ROTATION_EULER - The <MipTypes::Command> for this command
// FIELD_DATA_BYTE - 0x81 - The Data Field Descriptor byte
static const MipTypes::Command CMD_ID = MipTypes::CMD_EF_SENS_VEHIC_FRAME_ROTATION_EULER;
static const uint8 FIELD_DATA_BYTE = 0x81;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,9 @@ namespace mscl
DataBuffer buffer(response.data());
FilterInitializationValues data;

data.autoInitialize = !(buffer.read_uint8() > 0);
data.initialValuesSource = static_cast<FilterInitialValuesSource>(buffer.read_uint8());
data.autoHeadingAlignmentMethod = static_cast<HeadingAlignmentMethod>(buffer.read_uint8());
data.autoHeadingAlignmentMethod = HeadingAlignmentMethod(buffer.read_uint8());

float heading = buffer.read_float();
float pitch = buffer.read_float();
Expand Down Expand Up @@ -74,8 +75,9 @@ namespace mscl

if (m_functionSelector == MipTypes::USE_NEW_SETTINGS)
{
byteCommand.append_uint8(!m_data.autoInitialize);
byteCommand.append_uint8(static_cast<uint8>(m_data.initialValuesSource));
byteCommand.append_uint8(static_cast<uint8>(m_data.autoHeadingAlignmentMethod));
byteCommand.append_uint8(m_data.autoHeadingAlignmentMethod.value);
byteCommand.append_float(m_data.initialAttitude.heading());
byteCommand.append_float(m_data.initialAttitude.pitch());
byteCommand.append_float(m_data.initialAttitude.roll());
Expand Down
Loading

0 comments on commit 396a3c9

Please sign in to comment.