diff --git a/CHANGELOG.txt b/CHANGELOG.txt index eb1deb6fc..8e8a456b2 100644 --- a/CHANGELOG.txt +++ b/CHANGELOG.txt @@ -1,6 +1,155 @@ # MSCL Change Log All notable changes to this project will be documented in this file. +------------------------------------------------------------------------- +1.20.1 - 2015-10-29 +- added histogramEnable to FatigueOptions config. +- added supportsHistogramEnableConfig to NodeFeatures. + +------------------------------------------------------------------------- +1.20.0 - 2015-10-29 +- added fatigueMode to FatigueOptions config (replaces distributedAngleMode boolean). +- changed rawMode to debugMode in FatigueOptions. +- changed supportsFatigueRawModeConfig to supportsFatigueDebugModeConfig. +- added supportsFatigueModeConfig (replaces supportsFatigueDistributedAngleMode). +- added fatigueModes function to NodeFeatures for getting a list of supported fatigue modes. + +------------------------------------------------------------------------- +1.19.2 - 2015-10-28 +- changed back to std::regex...again. + +------------------------------------------------------------------------- +1.19.1 - 2015-10-27 +- fix for specific config issue enums not actually being returned. + +------------------------------------------------------------------------- +1.19.0 - 2015-10-27 +- added support for WirelessNode quickPing() command for performing a "Short Ping". + - this uses the new ASPP Short Ping if the Base Station supports it. +- changed from std::regex to boost::regex as the current Ubuntu LTS (14.04) doesn't support it. +- exposed InertialTypes::channelFieldToStr to SWIG. +- exposed InertialTypes::channelQualifierToStr to SWIG. +- exposed InertialTypes::channelName to SWIG. + +------------------------------------------------------------------------- +1.18.3 - 2015-10-27 +- added more specific config issue enums. +- fix for Gauge Factor config issue incorrectly sending a Hardware Gain issue enum. + +------------------------------------------------------------------------- +1.18.2 - 2015-10-26 +- fix for ActivitySense options not being written in the applyConfig function. + +------------------------------------------------------------------------- +1.18.1 - 2015-10-22 +- added support for the SG-Link-Micro node. + +------------------------------------------------------------------------- +1.18.0 - 2015-10-21 +- added support for the Fatigue distributed angle mode configuration. + +------------------------------------------------------------------------- +1.17.1 - 2015-10-21 +- added support for WirelessNode regionCode() function. +- removed optional frequency parameter from WirelessNode constructor. + +------------------------------------------------------------------------- +1.17.0 - 2015-10-21 +- added support for Gauge Factor configuration for supported nodes. + +------------------------------------------------------------------------- +1.16.0 - 2015-10-20 +- finalized support for ActivitySense feature. + +------------------------------------------------------------------------- +1.15.1 - 2015-10-20 +- added support for SHM-Link2-cust1 model. +- starting to add support for ActivitySense feature (not yet working, invalid eeproms). + +------------------------------------------------------------------------- +1.15.0 - 2015-10-19 +- added InertialNode::getAntennaOffset(). +- added InertialNode::setAntennaOffset(). + +------------------------------------------------------------------------- +1.14.0 - 2015-10-16 +- added InertialNode::getSensorToVehicleOffset(). +- added InertialNode::setSensorToVehicleOffset(). +- added start of InertialNodeFeatures class (doesn't provide anything right now). + +------------------------------------------------------------------------- +1.13.0 - 2015-10-15 +- added InertialNode::getSensorToVehicleTransformation(). +- added InertialNode::setSensorToVehicleTransformation(). + +------------------------------------------------------------------------- +1.12.2 - 2015-10-15 +- removing support for cal coefficients from the SHM-Link 2. + +------------------------------------------------------------------------- +1.12.1 - 2015-10-15 +- updated SHM-Link 2 features to not support limited duration (sweeps). + +------------------------------------------------------------------------- +1.12.0 - 2015-10-15 +- added NodeFeatures::supportsLimitedDuration for checking which Nodes only support unlimited sampling (no sweeps). +- don't allow a value other than true to be set for unlimited duration if Node doesn't support disabling it. +- don't allow reading or writing the number of sweeps if the node only supports unlimited sampling. +- NodeFeatures minSweeps and maxSweeps functions return 0 if the node only supports unlimited sampling. +- added sleep and up to 5 attempted pings after performing the BaseStation cycle power command. +- added sleep after performing the BaseStation reset radio command. +- added sleep and up to 5 attempted pings after performing the WirelessNode cycle power command. +- added sleep after performing the WirelessNode reset radio command. +- writing a disabled value of 0xFFFF to the channel value for analog base stations if set to 0xFF. + +------------------------------------------------------------------------- +1.11.4 - 2015-10-14 +- updated to changes made to auto balance 2 packet. +- changed WirelessNode::autoBalance command to take a float percentage range. +- changed AutoBalanceResult to have percent achieved instead of the channel sample value. +- removed resolution from all of the channels as the new autobalance made it unnecessary. + +------------------------------------------------------------------------- +1.11.3 - 2015-10-13 +- updated auto balance 2 command id. +- fix for cycle power on the base station failing if haven't determined protocol version. +- resetting the radio or cycling power when writing base eeproms (depending on firmware version). +- cycling the power on nodes when committing eeproms (instead of resetting radio). + +------------------------------------------------------------------------- +1.11.2 - 2015-10-13 +- made AutoBalanceResult functions const. + +------------------------------------------------------------------------- +1.11.1 - 2015-10-13 +- fix for WirelessNode::autobalance not returning the AutoBalanceResult. + +------------------------------------------------------------------------- +1.11.0 - 2015-10-13 +- support for old and new auto balance commands. +- old auto balance command now performs a hardware offset eeprom read. +- old auto balance command now performs a read single sensor to get the channel value. +- moved AutoCalResult to its own file. +- moved AutoBalanceResult to its own file. + +------------------------------------------------------------------------- +1.10.1 - 2015-10-12 +- changed WirelessNode's autobalance function to take a ChannelMask instead of a channel number. +- added method to get the resolution from each WirelessChannel object. +- adding start of the AutoBalance_v2 command (not fully functional). + +------------------------------------------------------------------------- +1.10.0 - 2015-10-09 +- added supportsLostBeaconTimeout() to the NodeFeatures class. + +------------------------------------------------------------------------- +1.9.2 - 2015-10-06 +- fix for mV/V-Link having incorrect model number. + +------------------------------------------------------------------------- +1.9.1 - 2015-10-05 +- added support for Wireless Nodes and BaseStations supporting new transmit powers. + ------------------------------------------------------------------------- 1.9.0 - 2015-10-02 - added support for the mV/V-Link Wireless Node. @@ -1002,7 +1151,7 @@ All notable changes to this project will be documented in this file. ------------------------------------------------------------------------- 0.4.0 2013-12-17 -- Switched from boost::any to my own customer any class (similar to boost::spirit::hold_any) to improve performance [internal]. +- Switched from boost::any to my own custom any class (similar to boost::spirit::hold_any) to improve performance [internal]. - Beginning of support for the SyncSamplingNetwork for creating and starting a Synchronized Sampling network. - Support for GetDeviceInfo and GetDeviceDescriptorSets for Inertial nodes [internal]. - Added InertialNode.info() to get information about the InertialNode. diff --git a/MSCL/Jamfile b/MSCL/Jamfile index bb5a272b4..26ee5f87a 100644 --- a/MSCL/Jamfile +++ b/MSCL/Jamfile @@ -38,6 +38,7 @@ alias msclSrcs [ glob source/mscl/MicroStrain/*.cpp ] [ glob source/mscl/MicroStrain/Inertial/*.cpp ] [ glob source/mscl/MicroStrain/Inertial/Commands/*.cpp ] + [ glob source/mscl/MicroStrain/Inertial/Features/*.cpp ] [ glob source/mscl/MicroStrain/Inertial/Packets/*.cpp ] [ glob source/mscl/MicroStrain/Wireless/*.cpp ] [ glob source/mscl/MicroStrain/Wireless/Commands/*.cpp ] diff --git a/MSCL/MSCL.vcxproj b/MSCL/MSCL.vcxproj index 29cb909e9..cae2c0fa1 100644 --- a/MSCL/MSCL.vcxproj +++ b/MSCL/MSCL.vcxproj @@ -655,6 +655,20 @@ + + + + + + + + + + + + + + @@ -672,6 +686,7 @@ + @@ -680,7 +695,10 @@ + + + @@ -690,8 +708,10 @@ + + @@ -699,6 +719,7 @@ + @@ -735,6 +756,7 @@ + @@ -800,6 +822,7 @@ + @@ -847,6 +870,20 @@ + + + + + + + + + + + + + + @@ -864,6 +901,7 @@ + @@ -872,7 +910,10 @@ + + + @@ -882,8 +923,10 @@ + + @@ -891,6 +934,7 @@ + @@ -927,6 +971,7 @@ + @@ -991,6 +1036,7 @@ + diff --git a/MSCL/MSCL.vcxproj.filters b/MSCL/MSCL.vcxproj.filters index ad6a54011..5722d2b17 100644 --- a/MSCL/MSCL.vcxproj.filters +++ b/MSCL/MSCL.vcxproj.filters @@ -43,6 +43,9 @@ {cecc2ab0-4168-4af7-b457-e8c1e4555354} + + {7096baca-9884-49f7-87b9-4807409caabc} + @@ -581,6 +584,75 @@ MicroStrain\Wireless\Features\Nodes + + MicroStrain\Wireless\Commands + + + MicroStrain\Wireless\Commands + + + MicroStrain\Wireless\Commands + + + MicroStrain\Wireless\Commands + + + Utils + + + MicroStrain\Inertial + + + MicroStrain\Inertial + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Wireless\Configuration + + + MicroStrain\Wireless\Features\Nodes + + + MicroStrain\Wireless\Commands + @@ -1091,6 +1163,75 @@ MicroStrain\Wireless\Features\Nodes + + MicroStrain\Wireless\Commands + + + MicroStrain\Wireless\Commands + + + MicroStrain\Wireless\Commands + + + MicroStrain\Wireless\Commands + + + Utils + + + MicroStrain\Inertial + + + MicroStrain\Inertial + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Inertial\Features + + + MicroStrain\Wireless\Configuration + + + MicroStrain\Wireless\Features\Nodes + + + MicroStrain\Wireless\Commands + diff --git a/MSCL/source/mscl/LibVersion.h b/MSCL/source/mscl/LibVersion.h index 311ea7ccb..527877ffe 100644 --- a/MSCL/source/mscl/LibVersion.h +++ b/MSCL/source/mscl/LibVersion.h @@ -12,8 +12,8 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #ifndef SWIG //update with each release #define MSCL_MAJOR 1 -#define MSCL_MINOR 9 -#define MSCL_PATCH 0 +#define MSCL_MINOR 20 +#define MSCL_PATCH 1 #endif namespace mscl diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/ContinuousDataStream.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Commands/ContinuousDataStream.cpp index 05fb52c65..c1db39e6a 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/ContinuousDataStream.cpp +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/ContinuousDataStream.cpp @@ -91,7 +91,7 @@ namespace mscl return GenericInertialCommand::Response::match_data(field); } - bool ContinuousDataStream::Response::parseData(const GenericInertialCommandResponse& response) const + bool ContinuousDataStream::Response::parseResponse(const GenericInertialCommandResponse& response) const { return Inertial_Commands::parseData_ContinuousDataStream(response); } diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/ContinuousDataStream.h b/MSCL/source/mscl/MicroStrain/Inertial/Commands/ContinuousDataStream.h index cd99ecb52..9ccd778e0 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/ContinuousDataStream.h +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/ContinuousDataStream.h @@ -86,7 +86,7 @@ namespace mscl // true if the field matches the expected data, false if it does not. virtual bool match_data(const InertialDataField& field) override; - //Function: parseData + //Function: parseResponse // Parses a successfully matched response for the ContinuousDataStream command. // //Parameters: @@ -94,7 +94,7 @@ namespace mscl // //Returns: // true if the data stream is enabled, false if it is disabled. - bool parseData(const GenericInertialCommandResponse& response) const; + bool parseResponse(const GenericInertialCommandResponse& response) const; }; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/EstFilter_Commands.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Commands/EstFilter_Commands.cpp index f9dc9275e..68c9a63cb 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/EstFilter_Commands.cpp +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/EstFilter_Commands.cpp @@ -8,6 +8,8 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #include "Inertial_Commands.h" #include "mscl/Utils.h" #include "mscl/Exceptions.h" +#include "mscl/MicroStrain/Inertial/EulerAngles.h" +#include "mscl/MicroStrain/Inertial/PositionOffset.h" namespace mscl { @@ -23,7 +25,7 @@ namespace mscl GenericInertialCommand::Response(collector, true, true, "Get Estimation Filter Data Rate Base") {} - uint16 GetEstFilterDataRateBase::Response::parseData(const GenericInertialCommandResponse& response) const + uint16 GetEstFilterDataRateBase::Response::parseResponse(const GenericInertialCommandResponse& response) const { return Inertial_Commands::parseData_DataRateBase(response); } @@ -82,9 +84,135 @@ namespace mscl GenericInertialCommand::Response(collector, true, dataResponse, "Estimation Filter Message Format") {} - InertialChannels EstFilterMessageFormat::Response::parseData(const GenericInertialCommandResponse& response, uint16 sampleRateBase) const + InertialChannels EstFilterMessageFormat::Response::parseResponse(const GenericInertialCommandResponse& response, uint16 sampleRateBase) const { return Inertial_Commands::parseData_MessageFormat(response, fieldDataByte(), sampleRateBase); } //========================================================================================== + + //========================================================================================== + //Sensor to Vehicle Frame Transformation + ByteStream SensorToVehicFrameTrans::buildCommand_get() + { + //container to hold the command's field data + ByteStream fieldData; + + //add the command selector byte + fieldData.append_uint8(static_cast(Inertial_Commands::cmd_getCurrent)); + + //build and return the command bytes + return GenericInertialCommand::buildCommand(CMD_ID, fieldData.data()); + } + + ByteStream SensorToVehicFrameTrans::buildCommand_set(const EulerAngles& angles) + { + //container to hold the command's field data + ByteStream fieldData; + + //add the command selector byte + fieldData.append_uint8(static_cast(Inertial_Commands::cmd_setCurrent)); + + //add the roll, pitch, yaw data + fieldData.append_float(angles.roll()); + fieldData.append_float(angles.pitch()); + fieldData.append_float(angles.yaw()); + + //build and return the command bytes + return GenericInertialCommand::buildCommand(CMD_ID, fieldData.data()); + } + + SensorToVehicFrameTrans::Response::Response(std::weak_ptr collector, bool dataResponse): + GenericInertialCommand::Response(collector, true, dataResponse, "Sensor to Vehicle Frame Transformation") + { + } + + EulerAngles SensorToVehicFrameTrans::Response::parseResponse(const GenericInertialCommandResponse& response) const + { + return Inertial_Commands::parseData_EulerAngles(response); + } + //========================================================================================== + + //========================================================================================== + //Sensor to Vehicle Frame Offset + ByteStream SensorToVehicFrameOffset::buildCommand_get() + { + //container to hold the command's field data + ByteStream fieldData; + + //add the command selector byte + fieldData.append_uint8(static_cast(Inertial_Commands::cmd_getCurrent)); + + //build and return the command bytes + return GenericInertialCommand::buildCommand(CMD_ID, fieldData.data()); + } + + ByteStream SensorToVehicFrameOffset::buildCommand_set(const PositionOffset& offset) + { + //container to hold the command's field data + ByteStream fieldData; + + //add the command selector byte + fieldData.append_uint8(static_cast(Inertial_Commands::cmd_setCurrent)); + + //add the x, y, z data + fieldData.append_float(offset.x()); + fieldData.append_float(offset.y()); + fieldData.append_float(offset.z()); + + //build and return the command bytes + return GenericInertialCommand::buildCommand(CMD_ID, fieldData.data()); + } + + SensorToVehicFrameOffset::Response::Response(std::weak_ptr collector, bool dataResponse): + GenericInertialCommand::Response(collector, true, dataResponse, "Sensor to Vehicle Frame Offset") + { + } + + PositionOffset SensorToVehicFrameOffset::Response::parseResponse(const GenericInertialCommandResponse& response) const + { + return Inertial_Commands::parseData_PositionOffset(response); + } + //========================================================================================== + + //========================================================================================== + //Antenna Offset + ByteStream AntennaOffset::buildCommand_get() + { + //container to hold the command's field data + ByteStream fieldData; + + //add the command selector byte + fieldData.append_uint8(static_cast(Inertial_Commands::cmd_getCurrent)); + + //build and return the command bytes + return GenericInertialCommand::buildCommand(CMD_ID, fieldData.data()); + } + + ByteStream AntennaOffset::buildCommand_set(const PositionOffset& offset) + { + //container to hold the command's field data + ByteStream fieldData; + + //add the command selector byte + fieldData.append_uint8(static_cast(Inertial_Commands::cmd_setCurrent)); + + //add the x, y, z data + fieldData.append_float(offset.x()); + fieldData.append_float(offset.y()); + fieldData.append_float(offset.z()); + + //build and return the command bytes + return GenericInertialCommand::buildCommand(CMD_ID, fieldData.data()); + } + + AntennaOffset::Response::Response(std::weak_ptr collector, bool dataResponse): + GenericInertialCommand::Response(collector, true, dataResponse, "Antenna Offset") + { + } + + PositionOffset AntennaOffset::Response::parseResponse(const GenericInertialCommandResponse& response) const + { + return Inertial_Commands::parseData_PositionOffset(response); + } + //========================================================================================== } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/EstFilter_Commands.h b/MSCL/source/mscl/MicroStrain/Inertial/Commands/EstFilter_Commands.h index f064a522c..6194dc08d 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/EstFilter_Commands.h +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/EstFilter_Commands.h @@ -12,6 +12,10 @@ namespace mscl { //Title: EstFilter_Commands + //forward declarations + class EulerAngles; + class PositionOffset; + //Class: GetEstFilterDataRateBase // Contains the logic for the "Get Estimation Filter Data Rate Base" command class GetEstFilterDataRateBase @@ -55,7 +59,7 @@ namespace mscl // Creates the Response object Response(std::weak_ptr collector); - //Function: parseData + //Function: parseResponse // Parses the response, getting the data rate base result // //Parameters: @@ -63,7 +67,7 @@ namespace mscl // //Returns: // The data rate base result - uint16 parseData(const GenericInertialCommandResponse& response) const; + uint16 parseResponse(const GenericInertialCommandResponse& response) const; }; }; @@ -111,7 +115,121 @@ namespace mscl public: Response(std::weak_ptr collector, bool dataResponse); - InertialChannels parseData(const GenericInertialCommandResponse& response, uint16 sampleRateBase) const; + InertialChannels parseResponse(const GenericInertialCommandResponse& response, uint16 sampleRateBase) const; + }; + }; + + //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 for this command + // FIELD_DATA_BYTE - 0x81 - The Data Field Descriptor byte + static const InertialTypes::Command CMD_ID = InertialTypes::CMD_EF_SENS_VEHIC_FRAME_TRANS; + static const uint8 FIELD_DATA_BYTE = 0x81; + + private: + SensorToVehicFrameTrans(); //disabled default constructor + + public: + //Function: buildCommand_get + // Builds the bytes for the "get" command. + static ByteStream buildCommand_get(); + + //Function: buildCommand_set + // Builds the bytes for the "set" command. + // + //Parameters: + // angles- The containing the roll, pitch, and yaw (in radians). + static ByteStream buildCommand_set(const EulerAngles& angles); + + class Response: public GenericInertialCommand::Response + { + protected: + virtual InertialTypes::Command commandId() const { return CMD_ID; } + virtual uint8 fieldDataByte() const { return FIELD_DATA_BYTE; } + + public: + Response(std::weak_ptr collector, bool dataResponse); + EulerAngles parseResponse(const GenericInertialCommandResponse& response) const; + }; + }; + + //Class: SensorToVehicFrameOffset + // Contains the logic for the "Sensor to Vehicle Frame Offset" command + class SensorToVehicFrameOffset + { + public: + //Constants: Packet Bytes + // CMD_ID - CMD_EF_SENS_VEHIC_FRAME_OFFSET - The for this command + // FIELD_DATA_BYTE - 0x82 - The Data Field Descriptor byte + static const InertialTypes::Command CMD_ID = InertialTypes::CMD_EF_SENS_VEHIC_FRAME_OFFSET; + static const uint8 FIELD_DATA_BYTE = 0x82; + + private: + SensorToVehicFrameOffset(); //disabled default constructor + + public: + //Function: buildCommand_get + // Builds the bytes for the "get" command. + static ByteStream buildCommand_get(); + + //Function: buildCommand_set + // Builds the bytes for the "set" command. + // + //Parameters: + // offset - The in meters. + static ByteStream buildCommand_set(const PositionOffset& offset); + + class Response: public GenericInertialCommand::Response + { + protected: + virtual InertialTypes::Command commandId() const { return CMD_ID; } + virtual uint8 fieldDataByte() const { return FIELD_DATA_BYTE; } + + public: + Response(std::weak_ptr collector, bool dataResponse); + PositionOffset parseResponse(const GenericInertialCommandResponse& response) const; + }; + }; + + //Class: AntennaOffset + // Contains the logic for the "Antenna Offset" command + class AntennaOffset + { + public: + //Constants: Packet Bytes + // CMD_ID - CMD_EF_ANTENNA_OFFSET - The for this command + // FIELD_DATA_BYTE - 0x83 - The Data Field Descriptor byte + static const InertialTypes::Command CMD_ID = InertialTypes::CMD_EF_ANTENNA_OFFSET; + static const uint8 FIELD_DATA_BYTE = 0x83; + + private: + AntennaOffset(); //disabled default constructor + + public: + //Function: buildCommand_get + // Builds the bytes for the "get" command. + static ByteStream buildCommand_get(); + + //Function: buildCommand_set + // Builds the bytes for the "set" command. + // + //Parameters: + // offset - The in meters. + static ByteStream buildCommand_set(const PositionOffset& offset); + + class Response: public GenericInertialCommand::Response + { + protected: + virtual InertialTypes::Command commandId() const { return CMD_ID; } + virtual uint8 fieldDataByte() const { return FIELD_DATA_BYTE; } + + public: + Response(std::weak_ptr collector, bool dataResponse); + PositionOffset parseResponse(const GenericInertialCommandResponse& response) const; }; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/GPS_Commands.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Commands/GPS_Commands.cpp index 0b5727881..aeb8e2486 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/GPS_Commands.cpp +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/GPS_Commands.cpp @@ -22,7 +22,7 @@ namespace mscl GenericInertialCommand::Response(collector, true, true, "Get GPS Data Rate Base") {} - uint16 GetGpsDataRateBase::Response::parseData(const GenericInertialCommandResponse& response) const + uint16 GetGpsDataRateBase::Response::parseResponse(const GenericInertialCommandResponse& response) const { return Inertial_Commands::parseData_DataRateBase(response); } @@ -80,7 +80,7 @@ namespace mscl GenericInertialCommand::Response(collector, true, dataResponse, "GPS Message Format") {} - InertialChannels GpsMessageFormat::Response::parseData(const GenericInertialCommandResponse& response, uint16 sampleRateBase) const + InertialChannels GpsMessageFormat::Response::parseResponse(const GenericInertialCommandResponse& response, uint16 sampleRateBase) const { return Inertial_Commands::parseData_MessageFormat(response, fieldDataByte(), sampleRateBase); } diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/GPS_Commands.h b/MSCL/source/mscl/MicroStrain/Inertial/Commands/GPS_Commands.h index a063b86a9..c987b5e33 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/GPS_Commands.h +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/GPS_Commands.h @@ -55,7 +55,7 @@ namespace mscl // Creates the Response object Response(std::weak_ptr collector); - //Function: parseData + //Function: parseResponse // Parses the response, getting the data rate base result // //Parameters: @@ -63,7 +63,7 @@ namespace mscl // //Returns: // The data rate base result - uint16 parseData(const GenericInertialCommandResponse& response) const; + uint16 parseResponse(const GenericInertialCommandResponse& response) const; }; }; @@ -111,7 +111,7 @@ namespace mscl public: Response(std::weak_ptr collector, bool dataResponse); - InertialChannels parseData(const GenericInertialCommandResponse& response, uint16 sampleRateBase) const; + InertialChannels parseResponse(const GenericInertialCommandResponse& response, uint16 sampleRateBase) const; }; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceDescriptorSets.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceDescriptorSets.cpp index 1e287e862..453b9f57a 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceDescriptorSets.cpp +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceDescriptorSets.cpp @@ -47,7 +47,7 @@ namespace mscl return GenericInertialCommand::Response::match_data(field); } - std::vector GetDeviceDescriptorSets::Response::parseData(const GenericInertialCommandResponse& response) const + std::vector GetDeviceDescriptorSets::Response::parseResponse(const GenericInertialCommandResponse& response) const { std::vector result; Inertial_Commands::parseData_GetDeviceDescriptorSets(response, result); diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceDescriptorSets.h b/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceDescriptorSets.h index 0230c4fcd..a632f7ae3 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceDescriptorSets.h +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceDescriptorSets.h @@ -55,7 +55,7 @@ namespace mscl // true if the field matches the expected data, false if it does not. virtual bool match_data(const InertialDataField& field) override; - //Function: parseData + //Function: parseResponse // Parses a successfully matched response for the GetDeviceDescriptorSets command. // //Parameters: @@ -63,7 +63,7 @@ namespace mscl // //Returns: // The descriptor sets parsed from the response. - std::vector parseData(const GenericInertialCommandResponse& response) const; + std::vector parseResponse(const GenericInertialCommandResponse& response) const; }; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceInfo.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceInfo.cpp index 7dbf1ccd0..0cfbff57f 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceInfo.cpp +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceInfo.cpp @@ -47,7 +47,7 @@ namespace mscl return GenericInertialCommand::Response::match_data(field); } - InertialDeviceInfo GetDeviceInfo::Response::parseData(const GenericInertialCommandResponse& response) const + InertialDeviceInfo GetDeviceInfo::Response::parseResponse(const GenericInertialCommandResponse& response) const { InertialDeviceInfo result; Inertial_Commands::parseData_GetDeviceInfo(response, result); diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceInfo.h b/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceInfo.h index f66e1748a..5d771ff85 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceInfo.h +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/GetDeviceInfo.h @@ -91,7 +91,7 @@ namespace mscl // true if the field matches the expected data, false if it does not. virtual bool match_data(const InertialDataField& field) override; - //Function: parseData + //Function: parseResponse // Parses a successfully matched response for the GetDeviceInfo command. // //Parameters: @@ -99,7 +99,7 @@ namespace mscl // //Returns: // The GetDeviceInfoResponse parsed from the response. - InertialDeviceInfo parseData(const GenericInertialCommandResponse& response) const; + InertialDeviceInfo parseResponse(const GenericInertialCommandResponse& response) const; }; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/Inertial_Commands.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Commands/Inertial_Commands.cpp index fad5b7313..6719e632e 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/Inertial_Commands.cpp +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/Inertial_Commands.cpp @@ -115,4 +115,34 @@ namespace mscl //return true if enabled, false if disabled return (response.data().read_uint8(1) == 1); //Note: position 0 is the device selector, which can be ignored here. } + + EulerAngles Inertial_Commands::parseData_EulerAngles(const GenericInertialCommandResponse& response) + { + //use a DataBuffer to make reading nicer + DataBuffer db(response.data()); + + //read the euler angles and store in the result + float roll = db.read_float(); + float pitch = db.read_float(); + float yaw = db.read_float(); + + EulerAngles result(roll, pitch, yaw); + + return result; + } + + PositionOffset Inertial_Commands::parseData_PositionOffset(const GenericInertialCommandResponse& response) + { + //use a DataBuffer to make reading nicer + DataBuffer db(response.data()); + + //read the euler angles and store in the result + float x = db.read_float(); + float y = db.read_float(); + float z = db.read_float(); + + PositionOffset result(x, y, z); + + return result; + } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/Inertial_Commands.h b/MSCL/source/mscl/MicroStrain/Inertial/Commands/Inertial_Commands.h index 29104f39d..37130a186 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/Inertial_Commands.h +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/Inertial_Commands.h @@ -6,8 +6,10 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #pragma once #include "GenericInertialCommand.h" +#include "mscl/MicroStrain/Inertial/EulerAngles.h" #include "mscl/MicroStrain/Inertial/InertialChannel.h" #include "mscl/MicroStrain/Inertial/InertialTypes.h" +#include "mscl/MicroStrain/Inertial/PositionOffset.h" #include "GetDeviceInfo.h" namespace mscl @@ -92,5 +94,25 @@ namespace mscl //Returns: // true if the data stream is enabled, false if it is disabled. static bool parseData_ContinuousDataStream(const GenericInertialCommandResponse& response); + + //Function: parseData_EulerAngles + // Parses the data from a command response containing just 3 Euler Angles (roll, pitch, yaw). + // + //Parameters: + // response - The that contains the data to be parsed + // + //Returns: + // The containing the result that is parsed. + static EulerAngles parseData_EulerAngles(const GenericInertialCommandResponse& response); + + //Function: parseData_PositionOffset + // Parses the data from a command response containing just 3 Position Offset values (x, y, z). + // + //Parameters: + // response - The that contains the data to be parsed + // + //Returns: + // The containing the result that is parsed. + static PositionOffset parseData_PositionOffset(const GenericInertialCommandResponse& response); }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/Sensor_Commands.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Commands/Sensor_Commands.cpp index 398b57e5d..69c0eb8fb 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/Sensor_Commands.cpp +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/Sensor_Commands.cpp @@ -24,7 +24,7 @@ namespace mscl GenericInertialCommand::Response(collector, true, true, "Get Sensor Data Rate Base") {} - uint16 GetSensorDataRateBase::Response::parseData(const GenericInertialCommandResponse& response) const + uint16 GetSensorDataRateBase::Response::parseResponse(const GenericInertialCommandResponse& response) const { return Inertial_Commands::parseData_DataRateBase(response); } @@ -83,7 +83,7 @@ namespace mscl GenericInertialCommand::Response(collector, true, dataResponse, "Sensor Message Format") {} - InertialChannels SensorMessageFormat::Response::parseData(const GenericInertialCommandResponse& response, uint16 sampleRateBase) const + InertialChannels SensorMessageFormat::Response::parseResponse(const GenericInertialCommandResponse& response, uint16 sampleRateBase) const { return Inertial_Commands::parseData_MessageFormat(response, fieldDataByte(), sampleRateBase); } diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/Sensor_Commands.h b/MSCL/source/mscl/MicroStrain/Inertial/Commands/Sensor_Commands.h index ff73438c9..eb6a889f2 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/Sensor_Commands.h +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/Sensor_Commands.h @@ -55,7 +55,7 @@ namespace mscl // Creates the Response object Response(std::weak_ptr collector); - //Function: parseData + //Function: parseResponse // Parses the response, getting the data rate base result // //Parameters: @@ -63,7 +63,7 @@ namespace mscl // //Returns: // The data rate base result - uint16 parseData(const GenericInertialCommandResponse& response) const; + uint16 parseResponse(const GenericInertialCommandResponse& response) const; }; }; @@ -112,7 +112,7 @@ namespace mscl public: Response(std::weak_ptr collector, bool dataResponse); - InertialChannels parseData(const GenericInertialCommandResponse& response, uint16 sampleRateBase) const; + InertialChannels parseResponse(const GenericInertialCommandResponse& response, uint16 sampleRateBase) const; }; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/System_Commands.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Commands/System_Commands.cpp index 1ef9038fc..fd45b2f14 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/System_Commands.cpp +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/System_Commands.cpp @@ -45,7 +45,7 @@ namespace mscl GenericInertialCommand::Response(collector, true, dataResponse, "Communication Mode") {} - uint8 CommunicationMode::Response::parseData(const GenericInertialCommandResponse& response) const + uint8 CommunicationMode::Response::parseResponse(const GenericInertialCommandResponse& response) const { return Inertial_Commands::parseData_CommunicationMode(response); } diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Commands/System_Commands.h b/MSCL/source/mscl/MicroStrain/Inertial/Commands/System_Commands.h index effd54b6c..fe17ee68e 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Commands/System_Commands.h +++ b/MSCL/source/mscl/MicroStrain/Inertial/Commands/System_Commands.h @@ -58,7 +58,7 @@ namespace mscl public: Response(std::weak_ptr collector, bool dataResponse); - uint8 parseData(const GenericInertialCommandResponse& response) const; + uint8 parseResponse(const GenericInertialCommandResponse& response) const; }; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/EulerAngles.cpp b/MSCL/source/mscl/MicroStrain/Inertial/EulerAngles.cpp new file mode 100644 index 000000000..06bbcb42f --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/EulerAngles.cpp @@ -0,0 +1,40 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" + +#include "EulerAngles.h" + +namespace mscl +{ + EulerAngles::EulerAngles(): + m_roll(0.0f), + m_pitch(0.0f), + m_yaw(0.0f) + { + } + + EulerAngles::EulerAngles(float roll, float pitch, float yaw): + m_roll(roll), + m_pitch(pitch), + m_yaw(yaw) + { + } + + float EulerAngles::roll() const + { + return m_roll; + } + + float EulerAngles::pitch() const + { + return m_pitch; + } + + float EulerAngles::yaw() const + { + return m_yaw; + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/EulerAngles.h b/MSCL/source/mscl/MicroStrain/Inertial/EulerAngles.h new file mode 100644 index 000000000..dfc88c222 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/EulerAngles.h @@ -0,0 +1,56 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +//PUBLIC_HEADER +#pragma once + +namespace mscl +{ + //API Class: EulerAngles + // Represents generic Euler Angles (roll, pitch, yaw). + class EulerAngles + { + private: + //Variable: m_roll; + // The roll value. + float m_roll; + + //Variable: m_pitch + // The pitch value. + float m_pitch; + + //Variable: m_yaw + // The yaw value. + float m_yaw; + + public: + EulerAngles(); + + //API Constructor: EulerAngles + // Creates an EulerAngles object. + EulerAngles(float roll, float pitch, float yaw); + + //API Function: roll + // Gets the roll angle. + // + //Returns: + // The roll Euler Angle. + float roll() const; + + //API Function: pitch + // Gets the pitch angle. + // + //Returns: + // The pitch Euler Angle. + float pitch() const; + + //API Function: yaw + // Gets the yaw angle. + // + //Returns: + // The yaw Euler Angle. + float yaw() const; + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures.cpp new file mode 100644 index 000000000..569f6b48b --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures.cpp @@ -0,0 +1,77 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" + +#include +#include + +#include "InertialNodeFeatures.h" +#include "InertialNodeFeatures_3dm.h" +#include "InertialNodeFeatures_3dm_gx2.h" +#include "InertialNodeFeatures_3dm_dh3.h" +#include "InertialNodeFeatures_3dm_gx3_15.h" +#include "InertialNodeFeatures_3dm_gx3_25.h" +#include "InertialNodeFeatures_3dm_gx3_35.h" +#include "InertialNodeFeatures_3dm_gx3_45.h" +#include "InertialNodeFeatures_3dm_gx4_15.h" +#include "InertialNodeFeatures_3dm_gx4_25.h" +#include "InertialNodeFeatures_3dm_gx4_45.h" +#include "InertialNodeFeatures_3dm_rq1_45.h" +#include "InertialNodeFeatures_fasA.h" + +namespace mscl +{ + InertialNodeFeatures::InertialNodeFeatures(const InertialNodeInfo& info): + m_nodeInfo(info) + { + } + + std::unique_ptr InertialNodeFeatures::create(const InertialNodeInfo& info) + { + switch(info.model()) + { + case InertialModels::node_3dm: + return std::unique_ptr(new InertialNodeFeatures_3dm(info)); + + case InertialModels::node_fasA: + return std::unique_ptr(new InertialNodeFeatures_fasA(info)); + + case InertialModels::node_3dm_gx2: + return std::unique_ptr(new InertialNodeFeatures_3dm_gx2(info)); + + case InertialModels::node_3dm_dh3: + return std::unique_ptr(new InertialNodeFeatures_3dm_dh3(info)); + + case InertialModels::node_3dm_gx3_15: + return std::unique_ptr(new InertialNodeFeatures_3dm_gx3_15(info)); + + case InertialModels::node_3dm_gx3_25: + return std::unique_ptr(new InertialNodeFeatures_3dm_gx3_25(info)); + + case InertialModels::node_3dm_gx3_35: + return std::unique_ptr(new InertialNodeFeatures_3dm_gx3_35(info)); + + case InertialModels::node_3dm_gx3_45: + return std::unique_ptr(new InertialNodeFeatures_3dm_gx3_45(info)); + + case InertialModels::node_3dm_gx4_15: + return std::unique_ptr(new InertialNodeFeatures_3dm_gx4_15(info)); + + case InertialModels::node_3dm_gx4_25: + return std::unique_ptr(new InertialNodeFeatures_3dm_gx4_25(info)); + + case InertialModels::node_3dm_gx4_45: + return std::unique_ptr(new InertialNodeFeatures_3dm_gx4_45(info)); + + case InertialModels::node_3dm_rq1_45: + return std::unique_ptr(new InertialNodeFeatures_3dm_rq1_45(info)); + + default: + //we don't know anything about this node, throw an exception + throw Error_NotSupported("The Inertial Node model (" + Utils::toStr(info.model()) + ", " + info.modelName() + " ) is not supported by MSCL."); + } + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures.h b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures.h new file mode 100644 index 000000000..bb8259419 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures.h @@ -0,0 +1,55 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +//PUBLIC_HEADER +#pragma once + +#include + +#include "mscl/MicroStrain/Inertial/InertialNodeInfo.h" + +namespace mscl +{ + //API Class: InertialNodeFeatures + // Contains information on which features are supported by an . + class InertialNodeFeatures + { + private: + InertialNodeFeatures(); //disabled default constructor + InertialNodeFeatures(const InertialNodeFeatures&); //disabled copy constructor + InertialNodeFeatures& operator=(const InertialNodeFeatures&); //disable assignment operator + + public: + virtual ~InertialNodeFeatures() {}; + + protected: + //Constructor: InertialNodeFeatures + // Creates a InertialNodeFeatures object. + // + //Parameters: + // info - An object representing standard information of the . + InertialNodeFeatures(const InertialNodeInfo& info); + + //Variable: m_nodeInfo + // The object containing basic information retreived from eeprom about the . + InertialNodeInfo m_nodeInfo; + + public: +#ifndef SWIG + //Function: create + // Builds and returns a InertialNodeFeatures pointer based on the given parameters. + // + //Parameters: + // info - An object representing standard information of the device. + // + //Returns: + // An InertialNodeFeatures unique_ptr. + // + //Exceptions: + // - : The Node model is not supported by MSCL. + static std::unique_ptr create(const InertialNodeInfo& info); +#endif + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm.cpp new file mode 100644 index 000000000..be92cd846 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm.cpp @@ -0,0 +1,15 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "InertialNodeFeatures_3dm.h" + +namespace mscl +{ + InertialNodeFeatures_3dm::InertialNodeFeatures_3dm(const InertialNodeInfo& info): + InertialNodeFeatures(info) + { + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm.h b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm.h new file mode 100644 index 000000000..f8c0d659c --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm.h @@ -0,0 +1,23 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "InertialNodeFeatures.h" + +namespace mscl +{ + //Class: InertialNodeFeatures_3dm + // Contains information on features for the 3DM Node. Inherits from . + class InertialNodeFeatures_3dm: public InertialNodeFeatures + { + public: + virtual ~InertialNodeFeatures_3dm() {}; + + //Constructor: InertialNodeFeatures_3dm + // Creates a InertialNodeFeatures_3dm object. + InertialNodeFeatures_3dm(const InertialNodeInfo& info); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_dh3.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_dh3.cpp new file mode 100644 index 000000000..9add0b958 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_dh3.cpp @@ -0,0 +1,15 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "InertialNodeFeatures_3dm_dh3.h" + +namespace mscl +{ + InertialNodeFeatures_3dm_dh3::InertialNodeFeatures_3dm_dh3(const InertialNodeInfo& info): + InertialNodeFeatures(info) + { + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_dh3.h b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_dh3.h new file mode 100644 index 000000000..66347dd83 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_dh3.h @@ -0,0 +1,23 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "InertialNodeFeatures.h" + +namespace mscl +{ + //Class: InertialNodeFeatures_3dm_dh3 + // Contains information on features for the 3DM-DH3 Node. Inherits from . + class InertialNodeFeatures_3dm_dh3: public InertialNodeFeatures + { + public: + virtual ~InertialNodeFeatures_3dm_dh3() {}; + + //Constructor: InertialNodeFeatures_3dm_dh3 + // Creates a InertialNodeFeatures_3dm_dh3 object. + InertialNodeFeatures_3dm_dh3(const InertialNodeInfo& info); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx2.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx2.cpp new file mode 100644 index 000000000..f0c944c2f --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx2.cpp @@ -0,0 +1,15 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "InertialNodeFeatures_3dm_gx2.h" + +namespace mscl +{ + InertialNodeFeatures_3dm_gx2::InertialNodeFeatures_3dm_gx2(const InertialNodeInfo& info): + InertialNodeFeatures(info) + { + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx2.h b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx2.h new file mode 100644 index 000000000..e5c965372 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx2.h @@ -0,0 +1,23 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "InertialNodeFeatures.h" + +namespace mscl +{ + //Class: InertialNodeFeatures_3dm_gx2 + // Contains information on features for the 3DM-GX2 Node. Inherits from . + class InertialNodeFeatures_3dm_gx2: public InertialNodeFeatures + { + public: + virtual ~InertialNodeFeatures_3dm_gx2() {}; + + //Constructor: InertialNodeFeatures_3dm_gx2 + // Creates a InertialNodeFeatures_3dm_gx2 object. + InertialNodeFeatures_3dm_gx2(const InertialNodeInfo& info); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_15.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_15.cpp new file mode 100644 index 000000000..580fd1619 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_15.cpp @@ -0,0 +1,15 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "InertialNodeFeatures_3dm_gx3_15.h" + +namespace mscl +{ + InertialNodeFeatures_3dm_gx3_15::InertialNodeFeatures_3dm_gx3_15(const InertialNodeInfo& info): + InertialNodeFeatures(info) + { + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_15.h b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_15.h new file mode 100644 index 000000000..791c91366 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_15.h @@ -0,0 +1,23 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "InertialNodeFeatures.h" + +namespace mscl +{ + //Class: InertialNodeFeatures_3dm_gx3_15 + // Contains information on features for the 3DM-GX3-15 Node. Inherits from . + class InertialNodeFeatures_3dm_gx3_15: public InertialNodeFeatures + { + public: + virtual ~InertialNodeFeatures_3dm_gx3_15() {}; + + //Constructor: InertialNodeFeatures_3dm_gx3_15 + // Creates a InertialNodeFeatures_3dm_gx3_15 object. + InertialNodeFeatures_3dm_gx3_15(const InertialNodeInfo& info); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_25.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_25.cpp new file mode 100644 index 000000000..49b19ac81 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_25.cpp @@ -0,0 +1,15 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "InertialNodeFeatures_3dm_gx3_25.h" + +namespace mscl +{ + InertialNodeFeatures_3dm_gx3_25::InertialNodeFeatures_3dm_gx3_25(const InertialNodeInfo& info): + InertialNodeFeatures(info) + { + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_25.h b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_25.h new file mode 100644 index 000000000..6c26e3aae --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_25.h @@ -0,0 +1,23 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "InertialNodeFeatures.h" + +namespace mscl +{ + //Class: InertialNodeFeatures_3dm_gx3_25 + // Contains information on features for the 3DM-GX3-25 Node. Inherits from . + class InertialNodeFeatures_3dm_gx3_25: public InertialNodeFeatures + { + public: + virtual ~InertialNodeFeatures_3dm_gx3_25() {}; + + //Constructor: InertialNodeFeatures_3dm_gx3_25 + // Creates a InertialNodeFeatures_3dm_gx3_25 object. + InertialNodeFeatures_3dm_gx3_25(const InertialNodeInfo& info); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_35.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_35.cpp new file mode 100644 index 000000000..fabb2c1aa --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_35.cpp @@ -0,0 +1,15 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "InertialNodeFeatures_3dm_gx3_35.h" + +namespace mscl +{ + InertialNodeFeatures_3dm_gx3_35::InertialNodeFeatures_3dm_gx3_35(const InertialNodeInfo& info): + InertialNodeFeatures(info) + { + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_35.h b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_35.h new file mode 100644 index 000000000..d7b8ab45c --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_35.h @@ -0,0 +1,23 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "InertialNodeFeatures.h" + +namespace mscl +{ + //Class: InertialNodeFeatures_3dm_gx3_35 + // Contains information on features for the 3DM-GX3-35 Node. Inherits from . + class InertialNodeFeatures_3dm_gx3_35: public InertialNodeFeatures + { + public: + virtual ~InertialNodeFeatures_3dm_gx3_35() {}; + + //Constructor: InertialNodeFeatures_3dm_gx3_35 + // Creates a InertialNodeFeatures_3dm_gx3_35 object. + InertialNodeFeatures_3dm_gx3_35(const InertialNodeInfo& info); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_45.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_45.cpp new file mode 100644 index 000000000..5d393e945 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_45.cpp @@ -0,0 +1,15 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "InertialNodeFeatures_3dm_gx3_45.h" + +namespace mscl +{ + InertialNodeFeatures_3dm_gx3_45::InertialNodeFeatures_3dm_gx3_45(const InertialNodeInfo& info): + InertialNodeFeatures(info) + { + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_45.h b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_45.h new file mode 100644 index 000000000..e7124bf89 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx3_45.h @@ -0,0 +1,23 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "InertialNodeFeatures.h" + +namespace mscl +{ + //Class: InertialNodeFeatures_3dm_gx3_45 + // Contains information on features for the 3DM-GX3-45 Node. Inherits from . + class InertialNodeFeatures_3dm_gx3_45: public InertialNodeFeatures + { + public: + virtual ~InertialNodeFeatures_3dm_gx3_45() {}; + + //Constructor: InertialNodeFeatures_3dm_gx3_45 + // Creates a InertialNodeFeatures_3dm_gx3_45 object. + InertialNodeFeatures_3dm_gx3_45(const InertialNodeInfo& info); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_15.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_15.cpp new file mode 100644 index 000000000..0fcef6402 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_15.cpp @@ -0,0 +1,15 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "InertialNodeFeatures_3dm_gx4_15.h" + +namespace mscl +{ + InertialNodeFeatures_3dm_gx4_15::InertialNodeFeatures_3dm_gx4_15(const InertialNodeInfo& info): + InertialNodeFeatures(info) + { + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_15.h b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_15.h new file mode 100644 index 000000000..66c78fb91 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_15.h @@ -0,0 +1,23 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "InertialNodeFeatures.h" + +namespace mscl +{ + //Class: InertialNodeFeatures_3dm_gx4_15 + // Contains information on features for the 3DM-GX4-15 Node. Inherits from . + class InertialNodeFeatures_3dm_gx4_15: public InertialNodeFeatures + { + public: + virtual ~InertialNodeFeatures_3dm_gx4_15() {}; + + //Constructor: InertialNodeFeatures_3dm_gx4_15 + // Creates a InertialNodeFeatures_3dm_gx4_15 object. + InertialNodeFeatures_3dm_gx4_15(const InertialNodeInfo& info); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_25.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_25.cpp new file mode 100644 index 000000000..50aaa9c13 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_25.cpp @@ -0,0 +1,15 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "InertialNodeFeatures_3dm_gx4_25.h" + +namespace mscl +{ + InertialNodeFeatures_3dm_gx4_25::InertialNodeFeatures_3dm_gx4_25(const InertialNodeInfo& info): + InertialNodeFeatures(info) + { + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_25.h b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_25.h new file mode 100644 index 000000000..7d0b13903 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_25.h @@ -0,0 +1,23 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "InertialNodeFeatures.h" + +namespace mscl +{ + //Class: InertialNodeFeatures_3dm_gx4_25 + // Contains information on features for the 3DM-GX4-25 Node. Inherits from . + class InertialNodeFeatures_3dm_gx4_25: public InertialNodeFeatures + { + public: + virtual ~InertialNodeFeatures_3dm_gx4_25() {}; + + //Constructor: InertialNodeFeatures_3dm_gx4_25 + // Creates a InertialNodeFeatures_3dm_gx4_25 object. + InertialNodeFeatures_3dm_gx4_25(const InertialNodeInfo& info); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_45.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_45.cpp new file mode 100644 index 000000000..204b81e0c --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_45.cpp @@ -0,0 +1,15 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "InertialNodeFeatures_3dm_gx4_45.h" + +namespace mscl +{ + InertialNodeFeatures_3dm_gx4_45::InertialNodeFeatures_3dm_gx4_45(const InertialNodeInfo& info): + InertialNodeFeatures(info) + { + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_45.h b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_45.h new file mode 100644 index 000000000..a75a2bdef --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_gx4_45.h @@ -0,0 +1,23 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "InertialNodeFeatures.h" + +namespace mscl +{ + //Class: InertialNodeFeatures_3dm_gx4_45 + // Contains information on features for the 3DM-GX4-45 Node. Inherits from . + class InertialNodeFeatures_3dm_gx4_45: public InertialNodeFeatures + { + public: + virtual ~InertialNodeFeatures_3dm_gx4_45() {}; + + //Constructor: InertialNodeFeatures_3dm_gx4_45 + // Creates a InertialNodeFeatures_3dm_gx4_45 object. + InertialNodeFeatures_3dm_gx4_45(const InertialNodeInfo& info); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_rq1_45.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_rq1_45.cpp new file mode 100644 index 000000000..e02929dbd --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_rq1_45.cpp @@ -0,0 +1,15 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "InertialNodeFeatures_3dm_rq1_45.h" + +namespace mscl +{ + InertialNodeFeatures_3dm_rq1_45::InertialNodeFeatures_3dm_rq1_45(const InertialNodeInfo& info): + InertialNodeFeatures(info) + { + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_rq1_45.h b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_rq1_45.h new file mode 100644 index 000000000..19d3d0e14 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_3dm_rq1_45.h @@ -0,0 +1,23 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "InertialNodeFeatures.h" + +namespace mscl +{ + //Class: InertialNodeFeatures_3dm_rq1_45 + // Contains information on features for the 3DM-RQ1-45 Node. Inherits from . + class InertialNodeFeatures_3dm_rq1_45: public InertialNodeFeatures + { + public: + virtual ~InertialNodeFeatures_3dm_rq1_45() {}; + + //Constructor: InertialNodeFeatures_3dm_rq1_45 + // Creates a InertialNodeFeatures_3dm_rq1_45 object. + InertialNodeFeatures_3dm_rq1_45(const InertialNodeInfo& info); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_fasA.cpp b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_fasA.cpp new file mode 100644 index 000000000..bbe188c13 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_fasA.cpp @@ -0,0 +1,15 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "InertialNodeFeatures_fasA.h" + +namespace mscl +{ + InertialNodeFeatures_fasA::InertialNodeFeatures_fasA(const InertialNodeInfo& info): + InertialNodeFeatures(info) + { + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_fasA.h b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_fasA.h new file mode 100644 index 000000000..a4db18242 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/Features/InertialNodeFeatures_fasA.h @@ -0,0 +1,23 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "InertialNodeFeatures.h" + +namespace mscl +{ + //Class: InertialNodeFeatures_fasA + // Contains information on features for the FAS-A Node. Inherits from . + class InertialNodeFeatures_fasA: public InertialNodeFeatures + { + public: + virtual ~InertialNodeFeatures_fasA() {}; + + //Constructor: InertialNodeFeatures_fasA + // Creates a InertialNodeFeatures_fasA object. + InertialNodeFeatures_fasA(const InertialNodeInfo& info); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/InertialNode.cpp b/MSCL/source/mscl/MicroStrain/Inertial/InertialNode.cpp index e065b4501..eb7b5cd9c 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/InertialNode.cpp +++ b/MSCL/source/mscl/MicroStrain/Inertial/InertialNode.cpp @@ -9,6 +9,7 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #include "mscl/Types.h" #include "mscl/Communication/SerialConnection.h" #include "mscl/MicroStrain/Inertial/Commands/Inertial_Commands.h" +#include "Features/InertialNodeFeatures.h" #include "Packets/InertialPacket.h" #include "InertialParser.h" #include "InertialNode_Impl.h" @@ -28,8 +29,15 @@ namespace mscl { } - //==================================================================================================================================================== - //The following functions just get pushes through the InertialNode_Impl class containing the implementation of all these functions + const InertialNodeInfo& InertialNode::info() + { + return m_impl->info(); + } + + const InertialNodeFeatures& InertialNode::features() + { + return m_impl->features(); + } InertialDataPacket InertialNode::getNextDataPacket(uint32 timeout) { @@ -74,11 +82,6 @@ namespace mscl m_impl->commandsTimeout(timeout); } - const InertialNodeInfo& InertialNode::info() - { - return m_impl->info(); - } - std::string InertialNode::name() { return deviceName(info().serialNumber()); @@ -129,5 +132,33 @@ namespace mscl m_impl->enableDataStream(category, enable); } - //==================================================================================================================================================== + EulerAngles InertialNode::getSensorToVehicleTransformation() + { + return m_impl->getSensorToVehicleTransformation(); + } + + void InertialNode::setSensorToVehicleTransformation(const EulerAngles& angles) + { + m_impl->setSensorToVehicleTransformation(angles); + } + + PositionOffset InertialNode::getSensorToVehicleOffset() + { + return m_impl->getSensorToVehicleOffset(); + } + + void InertialNode::setSensorToVehicleOffset(const PositionOffset& offset) + { + m_impl->setSensorToVehicleOffset(offset); + } + + PositionOffset InertialNode::getAntennaOffset() + { + return m_impl->getAntennaOffset(); + } + + void InertialNode::setAntennaOffset(const PositionOffset& offset) + { + m_impl->setAntennaOffset(offset); + } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/InertialNode.h b/MSCL/source/mscl/MicroStrain/Inertial/InertialNode.h index 0ece773d5..9fe1bc218 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/InertialNode.h +++ b/MSCL/source/mscl/MicroStrain/Inertial/InertialNode.h @@ -12,10 +12,14 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #include "Commands/InertialCmdResponse.h" #include "Packets/InertialDataPacket.h" #include "mscl/Communication/Connection.h" +#include "mscl/MicroStrain/Inertial/PositionOffset.h" +#include "mscl/MicroStrain/Inertial/EulerAngles.h" namespace mscl { + //forward declarations class InertialNode_Impl; + class InertialNodeFeatures; //API Class: InertialNode // A class representing a MicroStrain Inertial Node @@ -48,6 +52,31 @@ namespace mscl std::shared_ptr m_impl; public: + //API Function: info + // Gets for this Node. + // The first time this function is called, it will send multiple commands to the device to get all required information. + // Note: This will be invalid when the InertialNode is destroyed. + // + //Returns: + // A reference to the for this Node. + // + //Exceptions: + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : Information failed to be loaded for this Node. + const InertialNodeInfo& info(); + + //API Function: features + // Gets a reference to the for this device. + // Note: This will be invalid when the InertialNode is destroyed. + // + //Exceptions: + // - : The model is not supported by MSCL. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : Information failed to be loaded for this Node. + const InertialNodeFeatures& features(); + //API Function: deviceName // Static function for creating the universal sensor name that should be used for SensorCloud. // @@ -125,19 +154,6 @@ namespace mscl // timeout - The timeout (in milliseconds) to set for Inertial commands. void commandsTimeout(uint64 timeout); - //API Function: info - // Gets for this Node. - // The first time this function is called, it will send multiple commands to the device to get all required information. - // - //Returns: - // A reference to the for this Node. - // - //Exceptions: - // - : There was no response to the command. The command timed out. - // - : The command has failed. Check the error code for more details. - // - : Information failed to be loaded for this Node. - const InertialNodeInfo& info(); - //API Function: name // Gets the name of the InertialNode. This is the universal sensor name that should be used for uploading to SensorCloud. // This is the same as calling . @@ -264,6 +280,86 @@ namespace mscl // - : The command has failed. Check the error code for more details. // - : A connection error has occurred with the InertialNode. void enableDataStream(InertialTypes::InertialCategory category, bool enable = true); + + //API Function: getSensorToVehicleTransformation + // Gets the sensor to vehicle frame transformation matrix using roll, pitch, and yaw Euler angles. + // These angles define the rotation from the sensor body from to the fixed vehicle frame. + // + //Returns: + // The object containing the roll, pitch, and yaw result (in radians). + // + //Exceptions: + // - : The command is not supported by this Node. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : A connection error has occurred with the InertialNode. + EulerAngles getSensorToVehicleTransformation(); + + //API Function: setSensorToVehicleTransformation + // Sets the sensor to vehicle frame transformation matrix using roll, pitch, and yaw Euler angles (in radians). + // These angles define the rotation from the sensor body from to the fixed vehicle frame. + // + //Parameters: + // angles - The object containing the roll, pitch, and yaw (in radians) to set. + // + //Exceptions: + // - : The command is not supported by this Node. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : A connection error has occurred with the InertialNode. + void setSensorToVehicleTransformation(const EulerAngles& angles); + + //API Function: getSensorToVehicleOffset + // Gets the sensor to vehicle frame offset, expressed in the sensor frame. + // + //Returns: + // The object containing the x, y, and z position (in meters) result. + // + //Exceptions: + // - : The command is not supported by this Node. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : A connection error has occurred with the InertialNode. + PositionOffset getSensorToVehicleOffset(); + + //API Function: setSensorToVehicleOffset + // Sets the sensor to vehicle frame offset, expressed in the sensor frame. + // + //Parameters: + // offset - The object containing the x, y, and z position (in meters) to set. + // + //Exceptions: + // - : The command is not supported by this Node. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : A connection error has occurred with the InertialNode. + void setSensorToVehicleOffset(const PositionOffset& offset); + + //API Function: getAntennaOffset + // Gets the antenna offset, expressed in the sensor frame. + // + //Returns: + // The object containing the x, y, and z position (in meters) result. + // + //Exceptions: + // - : The command is not supported by this Node. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : A connection error has occurred with the InertialNode. + PositionOffset getAntennaOffset(); + + //API Function: setAntennaOffset + // Sets the antenna offset, expressed in the sensor frame. + // + //Parameters: + // offset - The object containing the x, y, and z position (in meters) to set. + // + //Exceptions: + // - : The command is not supported by this Node. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : A connection error has occurred with the InertialNode. + void setAntennaOffset(const PositionOffset& offset); }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/InertialNode_Impl.cpp b/MSCL/source/mscl/MicroStrain/Inertial/InertialNode_Impl.cpp index 1b995edf8..da2e619ad 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/InertialNode_Impl.cpp +++ b/MSCL/source/mscl/MicroStrain/Inertial/InertialNode_Impl.cpp @@ -16,6 +16,7 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #include "Commands/ContinuousDataStream.h" #include "Commands/Inertial_SetToIdle.h" #include "Commands/Resume.h" +#include "Features/InertialNodeFeatures.h" namespace mscl { @@ -33,7 +34,7 @@ namespace mscl m_parser.reset(new InertialParser(&m_packetCollector, m_responseCollector)); //register the parse function with the connection - m_connection.registerParser(std::bind(&InertialNode_Impl::parseData, this, std::placeholders::_1)); + m_connection.registerParser(std::bind(&InertialNode_Impl::parseResponse, this, std::placeholders::_1)); } InertialNode_Impl::~InertialNode_Impl() @@ -47,6 +48,36 @@ namespace mscl return m_lastCommTime; } + const InertialNodeInfo& InertialNode_Impl::info() + { + //if we haven't initialized the InertialNodeInfo + if(!m_nodeInfo) + { + //send the GetDeviceInfo command + InertialDeviceInfo deviceInfo = getDeviceInfo(); + + //send the GetDeviceDescriptorSets command + std::vector sets = getDescriptorSets(); + + //create an InertialNodeInfo object + m_nodeInfo.reset(new InertialNodeInfo(deviceInfo, sets)); + } + + return (*m_nodeInfo); + } + + const InertialNodeFeatures& InertialNode_Impl::features() + { + //if the features variable hasn't been set yet + if(m_features == NULL) + { + //set the features variable by creating a new NodeFeatures pointer + m_features = InertialNodeFeatures::create(info()); + } + + return *(m_features.get()); + } + const SampleRates& InertialNode_Impl::supportedSampleRates(InertialTypes::InertialCategory category) { SampleRates* rates = NULL; @@ -91,7 +122,7 @@ namespace mscl return *rates; } - void InertialNode_Impl::parseData(DataBuffer& data) + void InertialNode_Impl::parseResponse(DataBuffer& data) { //send the readBuffer to the parser to parse all the bytes m_parser->parse(data); @@ -100,24 +131,6 @@ namespace mscl data.shiftExtraToStart(); } - const InertialNodeInfo& InertialNode_Impl::info() - { - //if we haven't initialized the InertialNodeInfo - if(!m_nodeInfo) - { - //send the GetDeviceInfo command - InertialDeviceInfo deviceInfo = getDeviceInfo(); - - //send the GetDeviceDescriptorSets command - std::vector sets = getDescriptorSets(); - - //create an InertialNodeInfo object - m_nodeInfo.reset(new InertialNodeInfo(deviceInfo, sets)); - } - - return (*m_nodeInfo); - } - void InertialNode_Impl::getNextDataPacket(InertialDataPacket& packet, uint32 timeout)//timeout = 0 { //check if a connection error has occurred @@ -219,7 +232,7 @@ namespace mscl GetDeviceInfo::Response r(m_responseCollector); //send the command, wait for the response, and parse the result - return r.parseData(doInertialCmd(r, GetDeviceInfo::buildCommand(), GetDeviceInfo::CMD_ID, false)); + return r.parseResponse(doInertialCmd(r, GetDeviceInfo::buildCommand(), GetDeviceInfo::CMD_ID, false)); } std::vector InertialNode_Impl::getDescriptorSets() @@ -228,7 +241,7 @@ namespace mscl GetDeviceDescriptorSets::Response r(m_responseCollector); //send the command, wait for the response, and parse the result - return r.parseData(doInertialCmd(r, GetDeviceDescriptorSets::buildCommand(), GetDeviceDescriptorSets::CMD_ID, false)); + return r.parseResponse(doInertialCmd(r, GetDeviceDescriptorSets::buildCommand(), GetDeviceDescriptorSets::CMD_ID, false)); } uint16 InertialNode_Impl::getDataRateBase(InertialTypes::InertialCategory category) @@ -244,7 +257,7 @@ namespace mscl GetSensorDataRateBase::Response r(m_responseCollector); //send the command, wait for the response, and parse the result - m_sensorRateBase = r.parseData(doInertialCmd(r, GetSensorDataRateBase::buildCommand(), GetSensorDataRateBase::CMD_ID)); + m_sensorRateBase = r.parseResponse(doInertialCmd(r, GetSensorDataRateBase::buildCommand(), GetSensorDataRateBase::CMD_ID)); } return m_sensorRateBase; @@ -259,7 +272,7 @@ namespace mscl GetGpsDataRateBase::Response r(m_responseCollector); //send the command, wait for the response, and parse the result - m_gpsRateBase = r.parseData(doInertialCmd(r, GetGpsDataRateBase::buildCommand(), GetGpsDataRateBase::CMD_ID)); + m_gpsRateBase = r.parseResponse(doInertialCmd(r, GetGpsDataRateBase::buildCommand(), GetGpsDataRateBase::CMD_ID)); } return m_gpsRateBase; @@ -275,7 +288,7 @@ namespace mscl GetEstFilterDataRateBase::Response r(m_responseCollector); //send the command, wait for the response, and parse the result - m_estfilterRateBase = r.parseData(doInertialCmd(r, GetEstFilterDataRateBase::buildCommand(), GetEstFilterDataRateBase::CMD_ID)); + m_estfilterRateBase = r.parseResponse(doInertialCmd(r, GetEstFilterDataRateBase::buildCommand(), GetEstFilterDataRateBase::CMD_ID)); } return m_estfilterRateBase; @@ -296,7 +309,7 @@ namespace mscl SensorMessageFormat::Response r(m_responseCollector, true); //send the command, wait for the response, and parse the result - return r.parseData(doInertialCmd(r, SensorMessageFormat::buildCommand_get(), SensorMessageFormat::CMD_ID), sampleRateBase); + return r.parseResponse(doInertialCmd(r, SensorMessageFormat::buildCommand_get(), SensorMessageFormat::CMD_ID), sampleRateBase); } case InertialTypes::CATEGORY_GPS: @@ -305,7 +318,7 @@ namespace mscl GpsMessageFormat::Response r(m_responseCollector, true); //send the command, wait for the response, and parse the result - return r.parseData(doInertialCmd(r, GpsMessageFormat::buildCommand_get(), GpsMessageFormat::CMD_ID), sampleRateBase); + return r.parseResponse(doInertialCmd(r, GpsMessageFormat::buildCommand_get(), GpsMessageFormat::CMD_ID), sampleRateBase); } case InertialTypes::CATEGORY_ESTFILTER: @@ -315,7 +328,7 @@ namespace mscl EstFilterMessageFormat::Response r(m_responseCollector, true); //send the command, wait for the response, and parse the result - return r.parseData(doInertialCmd(r, EstFilterMessageFormat::buildCommand_get(), EstFilterMessageFormat::CMD_ID), sampleRateBase); + return r.parseResponse(doInertialCmd(r, EstFilterMessageFormat::buildCommand_get(), EstFilterMessageFormat::CMD_ID), sampleRateBase); } } } @@ -366,7 +379,7 @@ namespace mscl CommunicationMode::Response r(m_responseCollector, true); //send the command, wait for the response, and parse the result - return r.parseData(doInertialCmd(r, CommunicationMode::buildCommand_get(), CommunicationMode::CMD_ID)); + return r.parseResponse(doInertialCmd(r, CommunicationMode::buildCommand_get(), CommunicationMode::CMD_ID)); } void InertialNode_Impl::setCommunicationMode(uint8 communicationMode) @@ -389,5 +402,47 @@ namespace mscl //send the command and wait for the response doInertialCmd(r, ContinuousDataStream::buildCommand_set(category, enable), ContinuousDataStream::CMD_ID); } + + EulerAngles InertialNode_Impl::getSensorToVehicleTransformation() + { + SensorToVehicFrameTrans::Response r(m_responseCollector, true); + + return r.parseResponse(doInertialCmd(r, SensorToVehicFrameTrans::buildCommand_get(), SensorToVehicFrameTrans::CMD_ID)); + } + + void InertialNode_Impl::setSensorToVehicleTransformation(const EulerAngles& angles) + { + SensorToVehicFrameTrans::Response r(m_responseCollector, false); + + doInertialCmd(r, SensorToVehicFrameTrans::buildCommand_set(angles), SensorToVehicFrameTrans::CMD_ID); + } + + PositionOffset InertialNode_Impl::getSensorToVehicleOffset() + { + SensorToVehicFrameOffset::Response r(m_responseCollector, true); + + return r.parseResponse(doInertialCmd(r, SensorToVehicFrameOffset::buildCommand_get(), SensorToVehicFrameOffset::CMD_ID)); + } + + void InertialNode_Impl::setSensorToVehicleOffset(const PositionOffset& offset) + { + SensorToVehicFrameOffset::Response r(m_responseCollector, false); + + doInertialCmd(r, SensorToVehicFrameOffset::buildCommand_set(offset), SensorToVehicFrameOffset::CMD_ID); + } + + PositionOffset InertialNode_Impl::getAntennaOffset() + { + AntennaOffset::Response r(m_responseCollector, true); + + return r.parseResponse(doInertialCmd(r, AntennaOffset::buildCommand_get(), AntennaOffset::CMD_ID)); + } + + void InertialNode_Impl::setAntennaOffset(const PositionOffset& offset) + { + AntennaOffset::Response r(m_responseCollector, false); + + doInertialCmd(r, AntennaOffset::buildCommand_set(offset), AntennaOffset::CMD_ID); + } //============================================================================ } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/InertialNode_Impl.h b/MSCL/source/mscl/MicroStrain/Inertial/InertialNode_Impl.h index 318116460..fcf5e7e53 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/InertialNode_Impl.h +++ b/MSCL/source/mscl/MicroStrain/Inertial/InertialNode_Impl.h @@ -16,12 +16,16 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #include "Packets/InertialPacketCollector.h" #include "mscl/Communication/Connection.h" #include "mscl/MicroStrain/ResponseCollector.h" +#include "mscl/MicroStrain/Inertial/EulerAngles.h" +#include "mscl/MicroStrain/Inertial/PositionOffset.h" #include "mscl/Timestamp.h" namespace mscl { - class InertialParser; //forward declaration - class InertialNodeInfo; //forward declaration + //forward declarations + class InertialParser; + class InertialNodeInfo; + class InertialNodeFeatures; //Class: InertialNode_Impl // Contains the implementation for an . @@ -102,13 +106,17 @@ namespace mscl // A representing the last time communication was achieved with the InertialNode. Timestamp m_lastCommTime; + //Variable: m_features + // The containing the features for this device. + std::unique_ptr m_features; + private: - //Function: parseData + //Function: parseResponse // Callback function that parses any bytes that are in the read buffer to find packets or command responses // //Parameters: // data - The containing all the data to be parsed - void parseData(DataBuffer& data); + void parseResponse(DataBuffer& data); //Function: doInertialCmd // Performs a generic Inertial Command, sending the command bytes and waiting for the response. @@ -128,6 +136,29 @@ namespace mscl virtual GenericInertialCommandResponse doInertialCmd(GenericInertialCommand::Response& response, const ByteStream& command, InertialTypes::Command commandId, bool verifySupported=true); public: + //Function: info + // Gets the for this Node. + // The first time this function is called, it will send multiple commands to the device to get all required information. + // + //Returns: + // A reference to the for this Node. + // + //Exceptions: + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : Information failed to be loaded for this Node. + const InertialNodeInfo& info(); + + //Function: features + // Gets a reference to the for this device. + // + //Exceptions: + // - : The model is not supported by MSCL. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : Information failed to be loaded for this Node. + virtual const InertialNodeFeatures& features(); + //Function: lastCommunicationTime // Gets the for the last time we communicated with the InertialNode. const Timestamp& lastCommunicationTime() const; @@ -183,19 +214,6 @@ namespace mscl // timeout - The timeout (in milliseconds) to set for Inertial commands. void commandsTimeout(uint64 timeout); - //Function: info - // Gets the for this Node. - // The first time this function is called, it will send multiple commands to the device to get all required information. - // - //Returns: - // A reference to the for this Node. - // - //Exceptions: - // - : There was no response to the command. The command timed out. - // - : The command has failed. Check the error code for more details. - // - : Information failed to be loaded for this Node. - const InertialNodeInfo& info(); - private: //Function: getDeviceInfo // Gets information about the InertialNode. @@ -338,5 +356,74 @@ namespace mscl // - : The command, or , is not supported by this Node. // - : The command has failed. void enableDataStream(InertialTypes::InertialCategory category, bool enable); + + //Function: getSensorToVehicleTransformation + // Gets the sensor to vehicle frame transformation matrix using roll, pitch, and yaw Euler angles (in radians). + // + //Exceptions: + // - : The command or is not supported by this Node. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : A connection error has occurred with the InertialNode. + EulerAngles getSensorToVehicleTransformation(); + + //Function: setSensorToVehicleTransformation + // Sets the sensor to vehicle frame transformation matrix using roll, pitch, and yaw Euler angles (in radians). + // + //Parameters: + // angles - The object containing the roll, pitch, and yaw to set. + // + //Exceptions: + // - : The command is not supported by this Node. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : A connection error has occurred with the InertialNode. + void setSensorToVehicleTransformation(const EulerAngles& angles); + + //Function: getSensorToVehicleOffset + // Gets the sensor to vehicle frame offset, expressed in the sensor frame. + // + //Exceptions: + // - : The command is not supported by this Node. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : A connection error has occurred with the InertialNode. + PositionOffset getSensorToVehicleOffset(); + + //Function: setSensorToVehicleTransformation + // Sets the sensor to vehicle frame offset, expressed in the sensor frame. + // + //Parameters: + // offset - The object containing the x, y, and z position (in meters) to set. + // + //Exceptions: + // - : The command is not supported by this Node. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : A connection error has occurred with the InertialNode. + void setSensorToVehicleOffset(const PositionOffset& offset); + + //Function: getAntennaOffset + // Gets the antenna offset, expressed in the sensor frame. + // + //Exceptions: + // - : The command is not supported by this Node. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : A connection error has occurred with the InertialNode. + PositionOffset getAntennaOffset(); + + //Function: setAntennaOffset + // Sets the antenna offset, expressed in the sensor frame. + // + //Parameters: + // offset - The object containing the x, y, and z position (in meters) to set. + // + //Exceptions: + // - : The command is not supported by this Node. + // - : There was no response to the command. The command timed out. + // - : The command has failed. Check the error code for more details. + // - : A connection error has occurred with the InertialNode. + void setAntennaOffset(const PositionOffset& offset); }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/InertialTypes.h b/MSCL/source/mscl/MicroStrain/Inertial/InertialTypes.h index c99de9582..e732fc240 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/InertialTypes.h +++ b/MSCL/source/mscl/MicroStrain/Inertial/InertialTypes.h @@ -431,7 +431,23 @@ struct InertialTypes // A typedef for a , pair. typedef std::pair ChannelId; - //Function: channelFieldToStr + //Function: channelFieldToCategory + // Gets the for a . + // + //Parameters: + // channelId - The to get the category for. + // + //Returns: + // The for the given channel ID. + static InertialCategory channelFieldToCategory(InertialTypes::ChannelField channelField); + + struct ChannelIdHash + { + size_t operator()(InertialTypes::ChannelId channelId) const; + }; +#endif + + //API Function: channelFieldToStr // Gets a string representation of a . // //Parameters: @@ -441,7 +457,7 @@ struct InertialTypes // A string representation of the given . static std::string channelFieldToStr(ChannelField field); - //Function: channelQualifierToStr + //API Function: channelQualifierToStr // Gets a string representation of a . // //Parameters: @@ -451,7 +467,7 @@ struct InertialTypes // A string representation of the given . static std::string channelQualifierToStr(ChannelQualifier qualifier); - //Function: channelName + //API Function: channelName // Gets the name of the specified . // This is the universal channel name that should be used for uploading to SensorCloud. // @@ -466,22 +482,6 @@ struct InertialTypes // - : Unknown channel. static std::string channelName(ChannelField field, ChannelQualifier qualifier); - //Function: channelFieldToCategory - // Gets the for a . - // - //Parameters: - // channelId - The to get the category for. - // - //Returns: - // The for the given channel ID. - static InertialCategory channelFieldToCategory(InertialTypes::ChannelField channelField); - - struct ChannelIdHash - { - size_t operator()(InertialTypes::ChannelId channelId) const; - }; -#endif - private: //Const: CHANNEL_NAMES // An unordered_map mapping each to its respective name (universal SensorCloud name). diff --git a/MSCL/source/mscl/MicroStrain/Inertial/Packets/InertialPacket.h b/MSCL/source/mscl/MicroStrain/Inertial/Packets/InertialPacket.h index ed18c9c64..7f7c08a07 100644 --- a/MSCL/source/mscl/MicroStrain/Inertial/Packets/InertialPacket.h +++ b/MSCL/source/mscl/MicroStrain/Inertial/Packets/InertialPacket.h @@ -28,14 +28,14 @@ namespace mscl //===================================================================================================== enum MipAckNack { - MIP_ACK_NACK_ERROR_NONE = 0, + MIP_ACK_NACK_ERROR_NONE = 0, - MIP_ACK_NACK_ERROR_UNKNOWN_COMMAND = 1, - MIP_ACK_NACK_ERROR_CHECKSUM_INVALID = 2, - MIP_ACK_NACK_ERROR_PARAMETER_INVALID = 3, - MIP_ACK_NACK_ERROR_COMMAND_FAILED = 4, - MIP_ACK_NACK_ERROR_COMMAND_TIMEOUT = 5, - MIP_ACK_NACK_ERROR_UNKNOWN_DESCRIPTOR_SET = 6 + MIP_ACK_NACK_ERROR_UNKNOWN_COMMAND = 1, + MIP_ACK_NACK_ERROR_CHECKSUM_INVALID = 2, + MIP_ACK_NACK_ERROR_PARAMETER_INVALID = 3, + MIP_ACK_NACK_ERROR_COMMAND_FAILED = 4, + MIP_ACK_NACK_ERROR_COMMAND_TIMEOUT = 5, + MIP_ACK_NACK_ERROR_UNKNOWN_DESCRIPTOR_SET = 6 }; public: diff --git a/MSCL/source/mscl/MicroStrain/Inertial/PositionOffset.cpp b/MSCL/source/mscl/MicroStrain/Inertial/PositionOffset.cpp new file mode 100644 index 000000000..e6b037242 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/PositionOffset.cpp @@ -0,0 +1,40 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" + +#include "PositionOffset.h" + +namespace mscl +{ + PositionOffset::PositionOffset(): + m_x(0.0f), + m_y(0.0f), + m_z(0.0f) + { + } + + PositionOffset::PositionOffset(float x, float y, float z): + m_x(x), + m_y(y), + m_z(z) + { + } + + float PositionOffset::x() const + { + return m_x; + } + + float PositionOffset::y() const + { + return m_y; + } + + float PositionOffset::z() const + { + return m_z; + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Inertial/PositionOffset.h b/MSCL/source/mscl/MicroStrain/Inertial/PositionOffset.h new file mode 100644 index 000000000..2a2704840 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Inertial/PositionOffset.h @@ -0,0 +1,56 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +//PUBLIC_HEADER +#pragma once + +namespace mscl +{ + //API Class: PositionOffset + // Represents a position offset (x, y, z). + class PositionOffset + { + private: + //Variable: m_x; + // The x value. + float m_x; + + //Variable: m_y + // The y value. + float m_y; + + //Variable: m_z + // The z value. + float m_z; + + public: + PositionOffset(); + + //API Constructor: PositionOffset + // Creates a PositionOffset object. + PositionOffset(float x, float y, float z); + + //API Function: x + // Gets the x position offset. + // + //Returns: + // The x position offset. + float x() const; + + //API Function: y + // Gets the y position offset. + // + //Returns: + // The y position offset. + float y() const; + + //API Function: z + // Gets the z position offset. + // + //Returns: + // The z position offset. + float z() const; + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/BaseStation.cpp b/MSCL/source/mscl/MicroStrain/Wireless/BaseStation.cpp index f11fa197a..344079bcb 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/BaseStation.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/BaseStation.cpp @@ -329,13 +329,18 @@ namespace mscl return m_impl->node_erase(nodeAddress); } - void BaseStation::node_autoBalance(NodeAddress nodeAddress, uint8 channelNumber, uint16 targetVal) + bool BaseStation::node_autoBalance(const WirelessProtocol& protocol, NodeAddress nodeAddress, uint8 channelNumber, float targetPercent, AutoBalanceResult& result) { - m_impl->node_autoBalance(nodeAddress, channelNumber, targetVal); + return m_impl->node_autoBalance(protocol, nodeAddress, channelNumber, targetPercent, result); } bool BaseStation::node_autocal(NodeAddress nodeAddress, WirelessModels::NodeModel model, const Version& fwVersion, AutoCalResult& result) { return m_impl->node_autocal(nodeAddress, model, fwVersion, result); } + + bool BaseStation::node_readSingleSensor(NodeAddress nodeAddress, uint8 channelNumber, uint16& result) + { + return m_impl->node_readSingleSensor(nodeAddress, channelNumber, result); + } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/BaseStation.h b/MSCL/source/mscl/MicroStrain/Wireless/BaseStation.h index 2ec11e18e..734a9a664 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/BaseStation.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/BaseStation.h @@ -22,6 +22,7 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. namespace mscl { //forward declarations + class AutoBalanceResult; class AutoCalResult; class BaseStation_Impl; class BaseStationFeatures; @@ -605,16 +606,16 @@ namespace mscl const Timestamp& node_lastCommunicationTime(NodeAddress nodeAddress) const; //Function: node_shortPing - // Pings a specific node + // Pings a specific node. // //Parameters: - // nodeAddress - the node address of the node to ping + // nodeAddress - the node address of the node to ping. // //Returns: - // true if successfully pinged the node, false otherwise + // true if successfully pinged the node, false otherwise. // //Exceptions: - // - : A connection error has occurred with the BaseStation + // - : A connection error has occurred with the BaseStation. bool node_shortPing(NodeAddress nodeAddress); //Function: node_ping @@ -765,13 +766,18 @@ namespace mscl // Sends the AutoBalance command to a Node. // //Parameters: + // protocol - The for the Node. // nodeAddress - The node address of the Node to send the command to. // channelNumber - The channel number (ch1 = 1, ch8 = 8) to balance. - // targetVal - The target value to balance to. + // targetPercent - The target percentage (0 - 100) to balance to. + // result - The of the command. + // + //Returns: + // true if the command succeeded, false if it failed. // //Exceptions: // - : A connection error has occurred with the BaseStation. - void node_autoBalance(NodeAddress nodeAddress, uint8 channelNumber, uint16 targetVal); + bool node_autoBalance(const WirelessProtocol& protocol, NodeAddress nodeAddress, uint8 channelNumber, float targetPercent, AutoBalanceResult& result); //Function: node_autocal // Performs automatic calibration for a Wireless Node. @@ -788,6 +794,21 @@ namespace mscl //Exceptions: // - : A connection error has occurred with the BaseStation. bool node_autocal(NodeAddress nodeAddress, WirelessModels::NodeModel model, const Version& fwVersion, AutoCalResult& result); + + //Function: node_readSingleSensor + // Reads the bits value for a single channel on a Wireless Node. + // + //Parameters: + // nodeAddress - The node address of the Node to send the command to. + // channelNumber - The channel number (ch1 = 1, ch8 = 8) to read. + // result - Holds the bits value result from the channel on the Node. + // + //Returns: + // true if the Read Single Sensor command was successful, false otherwise. + // + //Exceptions: + // - : A connection error has occurred with the BaseStation. + bool node_readSingleSensor(NodeAddress nodeAddress, uint8 channelNumber, uint16& result); #endif }; diff --git a/MSCL/source/mscl/MicroStrain/Wireless/BaseStation_Impl.cpp b/MSCL/source/mscl/MicroStrain/Wireless/BaseStation_Impl.cpp index 7ceed4087..61a667a2b 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/BaseStation_Impl.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/BaseStation_Impl.cpp @@ -12,6 +12,7 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #include "Configuration/BaseStationConfig.h" #include "Features/BaseStationFeatures.h" #include "mscl/MicroStrain/ResponsePattern.h" +#include "mscl/ScopeHelper.h" #include "mscl/Utils.h" #include "mscl/Version.h" #include "BaseStationInfo.h" @@ -32,20 +33,24 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. //Node commands #include "Commands/ArmForDatalogging.h" #include "Commands/AutoBalance.h" +#include "Commands/AutoBalance_v2.h" #include "Commands/AutoCal.h" -#include "Commands/ShortPing.h" +#include "Commands/AutoCalResult.h" +#include "Commands/Erase.h" #include "Commands/LongPing.h" +#include "Commands/PageDownload.h" #include "Commands/ReadEeprom.h" #include "Commands/ReadEeprom_v2.h" -#include "Commands/WriteEeprom.h" -#include "Commands/WriteEeprom_v2.h" -#include "Commands/PageDownload.h" -#include "Commands/StartNonSyncSampling.h" -#include "Commands/StartSyncSampling.h" +#include "Commands/ReadSingleSensor.h" #include "Commands/SetToIdle.h" +#include "Commands/ShortPing.h" +#include "Commands/ShortPing_v2.h" #include "Commands/Sleep.h" +#include "Commands/StartNonSyncSampling.h" +#include "Commands/StartSyncSampling.h" #include "Commands/TriggerArmedDatalogging.h" -#include "Commands/Erase.h" +#include "Commands/WriteEeprom.h" +#include "Commands/WriteEeprom_v2.h" namespace mscl { @@ -78,6 +83,10 @@ namespace mscl Version fwVersion; uint8 origRetries = m_eeprom->getNumRetries(); + + //when this goes out of scope, the number of retries will be changed back to what it was before + ScopeHelper writebackRetries(std::bind(&BaseStationEeprom::setNumRetries, m_eeprom.get(), origRetries)); + m_eeprom->setNumRetries(0); bool success = false; @@ -122,20 +131,8 @@ namespace mscl } while(!success && (retryCount++ < origRetries)); - //reset the eeprom retry counter back to what it was - m_eeprom->setNumRetries(origRetries); - - //the BaseStation min fw version to support protocol 1.1 - static const Version FW_PROTOCOL_1_1(4, 0); - - if(fwVersion >= FW_PROTOCOL_1_1) - { - return WirelessProtocol::v1_1(); - } - else - { - return WirelessProtocol::v1_0(); - } + //get the protocol to use for the base station's fw version + return WirelessProtocol::chooseBaseStationProtocol(fwVersion); } BaseStationEepromHelper& BaseStation_Impl::eeHelper() const @@ -734,6 +731,54 @@ namespace mscl return false; } + bool BaseStation_Impl::node_shortPing_v1(NodeAddress nodeAddress) + { + //create the response for the short ping command + ShortPing::Response response(m_responseCollector); + + //send the short ping command to the base station + m_connection.write(ShortPing::buildCommand(nodeAddress)); + + //wait for the response + response.wait(m_nodeCommandsTimeout); + + if(response.success()) + { + //update basestation last comm time + m_lastCommTime.setTimeNow(); + + //update node last comm time + m_nodesLastCommTime[nodeAddress].setTimeNow(); + } + + //return the result of the response + return response.success(); + } + + bool BaseStation_Impl::node_shortPing_v2(NodeAddress nodeAddress) + { + //create the response for the short ping command + ShortPing_v2::Response response(nodeAddress, m_responseCollector); + + //send the short ping command to the base station + m_connection.write(ShortPing_v2::buildCommand(nodeAddress)); + + //wait for the response + response.wait(m_nodeCommandsTimeout); + + if(response.success()) + { + //update basestation last comm time + m_lastCommTime.setTimeNow(); + + //update node last comm time + m_nodesLastCommTime[nodeAddress].setTimeNow(); + } + + //return the result of the response + return response.success(); + } + bool BaseStation_Impl::node_readEeprom_v1(NodeAddress nodeAddress, uint16 eepromAddress, uint16& eepromValue) { bool success = false; @@ -870,6 +915,57 @@ namespace mscl return success; } + bool BaseStation_Impl::node_autoBalance_v1(NodeAddress nodeAddress, uint8 channelNumber, float targetPercent, AutoBalanceResult& result) + { + //determine the target value to send to the autobalance command (max bits is always 4096 for this command) + uint16 targetVal = static_cast(4096 * targetPercent / 100.0f); + + //build the command to send + ByteStream command = AutoBalance::buildCommand(nodeAddress, channelNumber, targetVal); + + //send the command to the base station + m_connection.write(command); + + //this command doesn't have a response (no info), so set the error code to legacy + result.m_errorCode = WirelessTypes::autobalance_legacyNone; + + //don't know the actual status, have to assume success + return true; + } + + bool BaseStation_Impl::node_autoBalance_v2(NodeAddress nodeAddress, uint8 channelNumber, float targetPercent, AutoBalanceResult& result) + { + bool success = false; + + //create the response for the AutoBalance_v2 command + AutoBalance_v2::Response response(nodeAddress, channelNumber, targetPercent, m_responseCollector); + + //build the command to send + ByteStream command = AutoBalance_v2::buildCommand(nodeAddress, channelNumber, targetPercent); + + //send the command to the base station + m_connection.write(command); + + //wait for the response + response.wait(m_nodeCommandsTimeout); + + //return the result of the response + success = response.success(); + + if(success) + { + //update basestation last comm time + m_lastCommTime.setTimeNow(); + + //update node last comm time + m_nodesLastCommTime[nodeAddress].setTimeNow(); + } + + result = response.result(); + + return success; + } + Value BaseStation_Impl::readEeprom(const EepromLocation& location) const { return m_eeprom->readEeprom(location); @@ -897,6 +993,13 @@ namespace mscl //store the original timeout that is currently set uint64 originalTimeout = baseCommandsTimeout(); + //when this goes out of scope, it will write back the original timeout (need cast for overloaded ambiguity) + ScopeHelper writebackTimeout(std::bind(static_cast(&BaseStation_Impl::baseCommandsTimeout), this, originalTimeout)); + + //force determining of the protocol if it hasn't been already + //Note: this is so that we can set the timeout short and write eeprom without worrying about reading + protocol(); + try { //this command doesn't have a response, change to a quick timeout @@ -910,8 +1013,16 @@ namespace mscl //an exception will be thrown due to no response, just continue on } - //set the timeout back to what it was - baseCommandsTimeout(originalTimeout); + Utils::threadSleep(100); + + //attempt to ping the node a few times to see if its back online + bool pingSuccess = false; + uint8 retries = 0; + while(!pingSuccess && retries <= 5) + { + pingSuccess = ping(); + retries++; + } } void BaseStation_Impl::resetRadio() @@ -920,6 +1031,8 @@ namespace mscl //write a 0x02 to the CYCLE_POWER eeprom location on the base station writeEeprom(BaseStationEepromMap::CYCLE_POWER, Value::UINT16(RESET_RADIO)); + + Utils::threadSleep(100); } void BaseStation_Impl::changeFrequency(WirelessTypes::Frequency frequency) @@ -946,6 +1059,16 @@ namespace mscl void BaseStation_Impl::applyConfig(const BaseStationConfig& config) { config.apply(features(), eeHelper()); + + //if we can just reset the radio to commit the changes + if(features().supportsEepromCommitViaRadioReset()) + { + resetRadio(); + } + else + { + cyclePower(); + } } WirelessTypes::TransmitPower BaseStation_Impl::getTransmitPower() const @@ -997,30 +1120,6 @@ namespace mscl return m_nodesLastCommTime[nodeAddress]; } - bool BaseStation_Impl::node_shortPing(NodeAddress nodeAddress) - { - //create the response for the short ping command - ShortPing::Response response(m_responseCollector); - - //send the short ping command to the base station - m_connection.write(ShortPing::buildCommand(nodeAddress)); - - //wait up to 50 milliseconds for the response - response.wait(50); - - if(response.success()) - { - //update basestation last comm time - m_lastCommTime.setTimeNow(); - - //update node last comm time - m_nodesLastCommTime[nodeAddress].setTimeNow(); - } - - //return the result of the response - return response.success(); - } - PingResponse BaseStation_Impl::node_ping(NodeAddress nodeAddress) { //create the response for the LongPing command with the node address @@ -1081,6 +1180,12 @@ namespace mscl return status; } + bool BaseStation_Impl::node_shortPing(NodeAddress nodeAddress) + { + //this just depends on the protocol of the Base Station, not the Node + return protocol().m_shortPing(this, nodeAddress); + } + bool BaseStation_Impl::node_readEeprom(const WirelessProtocol& nodeProtocol, NodeAddress nodeAddress, uint16 eepromAddress, uint16& eepromValue) { return nodeProtocol.m_readNodeEeprom(this, nodeAddress, eepromAddress, eepromValue); @@ -1196,15 +1301,9 @@ namespace mscl return response.success(); } - void BaseStation_Impl::node_autoBalance(NodeAddress nodeAddress, uint8 channelNumber, uint16 targetVal) + bool BaseStation_Impl::node_autoBalance(const WirelessProtocol& nodeProtocol, NodeAddress nodeAddress, uint8 channelNumber, float targetPercent, AutoBalanceResult& result) { - //build the command to send - ByteStream command = AutoBalance::buildCommand(nodeAddress, channelNumber, targetVal); - - //send the command to the base station - m_connection.write(command); - - //no response for this command + return nodeProtocol.m_autoBalance(this, nodeAddress, channelNumber, targetPercent, result); } bool BaseStation_Impl::node_autocal(NodeAddress nodeAddress, WirelessModels::NodeModel model, const Version& fwVersion, AutoCalResult& result) @@ -1217,6 +1316,7 @@ namespace mscl switch(model) { case WirelessModels::node_shmLink2: + case WirelessModels::node_shmLink2_cust1: default: cmd = AutoCal::buildCommand_shmLink(nodeAddress); break; @@ -1256,4 +1356,30 @@ namespace mscl return response.success(); } + + bool BaseStation_Impl::node_readSingleSensor(NodeAddress nodeAddress, uint8 channelNumber, uint16& result) + { + //create the response for the Erase command + ReadSingleSensor::Response response(m_responseCollector); + + //send the erase command to the base station + m_connection.write(ReadSingleSensor::buildCommand(nodeAddress, channelNumber)); + + //wait for the response or timeout + response.wait(m_nodeCommandsTimeout); + + if(response.success()) + { + result = response.sensorValue(); + + //update basestation last comm time + m_lastCommTime.setTimeNow(); + + //update node last comm time + m_nodesLastCommTime[nodeAddress].setTimeNow(); + } + + //return the result of the response + return response.success(); + } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/BaseStation_Impl.h b/MSCL/source/mscl/MicroStrain/Wireless/BaseStation_Impl.h index 3bb418edb..76ec08eb9 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/BaseStation_Impl.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/BaseStation_Impl.h @@ -9,6 +9,7 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #include "WirelessParser.h" #include "WirelessModels.h" +#include "Commands/AutoBalance_v2.h" #include "Commands/BaseStation_BeaconStatus.h" #include "Commands/LongPing.h" #include "Commands/SetToIdleStatus.h" @@ -23,12 +24,13 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. namespace mscl { //forward declarations + class AutoBalanceResult; + class AutoCalResult; class BaseStation; class BaseStationFeatures; class BaseStationConfig; - class AutoCalResult; - class WirelessProtocol; class ResponsePattern; + class WirelessProtocol; //Class: BaseStation_Impl // Contains the implementation for a object. @@ -768,6 +770,32 @@ namespace mscl // - : A connection error has occurred with the BaseStation bool node_pageDownload_v1(NodeAddress nodeAddress, uint16 pageIndex, ByteStream& data); + //Function: node_shortPing_v1 + // Performs Version 1 of the Node Short Ping command. + // + //Parameters: + // nodeAddress - The node address of the Node to short ping. + // + //Returns: + // true if the short ping command succeeded, false otherwise. + // + //Exceptions: + // - : A connection error has occurred with the BaseStation. + bool node_shortPing_v1(NodeAddress nodeAddress); + + //Function: node_shortPing_v2 + // Performs Version 2 of the Node Short Ping command. + // + //Parameters: + // nodeAddress - The node address of the Node to short ping. + // + //Returns: + // true if the short ping command succeeded, false otherwise. + // + //Exceptions: + // - : A connection error has occurred with the BaseStation. + bool node_shortPing_v2(NodeAddress nodeAddress); + //Function: node_readEeprom_v1 // Performs Version 1 of the Node Read Eeprom command. // @@ -830,26 +858,45 @@ namespace mscl // - : A connection error has occurred with the BaseStation bool node_writeEeprom_v2(NodeAddress nodeAddress, uint16 eepromAddress, uint16 value); - public: - //Function: node_lastCommunicationTime - // Gets the for the last time MSCL communicated with the given node address. + //Function: node_autoBalance_v1 + // Performs Version 1 of the Node AutoBalance command. // //Parameters: - // nodeAddress - The node address of the Node to check for. - const Timestamp& node_lastCommunicationTime(NodeAddress nodeAddress); + // nodeAddress - The node address of the Node to send the command to. + // channelNumber - The channel number (ch1 = 1, ch8 = 8) to balance. + // targetPercent - The target percentage (0 - 100) to balance to. + // result - The of the command (empty in the case of v1). + // + //Returns: + // true if the command succeeded, false if it failed. + // + //Exceptions: + // - : A connection error has occurred with the BaseStation. + bool node_autoBalance_v1(NodeAddress nodeAddress, uint8 channelNumber, float targetPercent, AutoBalanceResult& result); - //Function: node_shortPing - // Pings a specific node + //Function: node_autoBalance_v2 + // Performs Version 2 of the Node AutoBalance command. // //Parameters: - // nodeAddress - the node address of the node to ping + // nodeAddress - The node address of the Node to send the command to. + // channelNumber - The channel number (ch1 = 1, ch8 = 8) to balance. + // targetPercent - The target percentage (0 - 100) to balance to. + // result - The of the command. // //Returns: - // true if successfully pinged the node, false otherwise + // true if the command succeeded, false if it failed. // //Exceptions: // - : A connection error has occurred with the BaseStation. - bool node_shortPing(NodeAddress nodeAddress); + bool node_autoBalance_v2(NodeAddress nodeAddress, uint8 channelNumber, float targetPercent, AutoBalanceResult& result); + + public: + //Function: node_lastCommunicationTime + // Gets the for the last time MSCL communicated with the given node address. + // + //Parameters: + // nodeAddress - The node address of the Node to check for. + const Timestamp& node_lastCommunicationTime(NodeAddress nodeAddress); //Function: node_ping // Pings the specified Node. @@ -892,6 +939,19 @@ namespace mscl // - : A connection error has occurred with the BaseStation. virtual SetToIdleStatus node_setToIdle(NodeAddress nodeAddress, const BaseStation& base); + //Function: node_shortPing + // Pings a specific node. + // + //Parameters: + // nodeAddress - the node address of the node to ping. + // + //Returns: + // true if successfully pinged the node, false otherwise + // + //Exceptions: + // - : A connection error has occurred with the BaseStation. + bool node_shortPing(NodeAddress nodeAddress); + //Function: node_readEeprom // Reads a value from EEPROM on the specified Node. // @@ -1003,13 +1063,18 @@ namespace mscl // Sends the AutoBalance command to a Node. // //Parameters: + // nodeProtocol - The for the Node. // nodeAddress - The node address of the Node to send the command to. // channelNumber - The channel number (ch1 = 1, ch8 = 8) to balance. - // targetVal - The target value to balance to. + // targetPercent - The target percentage (0 - 100) to balance to. + // result - The of the command. + // + //Returns: + // true if the command succeeded, false if it failed. // //Exceptions: // - : A connection error has occurred with the BaseStation. - virtual void node_autoBalance(NodeAddress nodeAddress, uint8 channelNumber, uint16 targetVal); + virtual bool node_autoBalance(const WirelessProtocol& nodeProtocol, NodeAddress nodeAddress, uint8 channelNumber, float targetPercent, AutoBalanceResult& result); //Function: node_autocal // Performs automatic calibration for a Wireless Node. @@ -1026,5 +1091,20 @@ namespace mscl //Exceptions: // - : A connection error has occurred with the BaseStation. bool node_autocal(NodeAddress nodeAddress, WirelessModels::NodeModel model, const Version& fwVersion, AutoCalResult& result); + + //Function: node_readSingleSensor + // Reads the bits value for a single channel on a Wireless Node. + // + //Parameters: + // nodeAddress - The node address of the Node to send the command to. + // channelNumber - The channel number (ch1 = 1, ch8 = 8) to read. + // result - Holds the bits value result from the channel on the Node. + // + //Returns: + // true if the Read Single Sensor command was successful, false otherwise. + // + //Exceptions: + // - : A connection error has occurred with the BaseStation. + bool node_readSingleSensor(NodeAddress nodeAddress, uint8 channelNumber, uint16& result); }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalance.h b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalance.h index e28808a40..78996d8c0 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalance.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalance.h @@ -27,7 +27,7 @@ namespace mscl //Parameters: // nodeAddress - The address of the Node to build the command for. // channelNumber - The channel number to balance (ch1 = 1, ch8 = 8). - // targetValue - The target sensor output value in bits. + // targetValue - The target sensor output value in bits (0-4096). // //Returns: // A containing the command packet. diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalanceResult.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalanceResult.cpp new file mode 100644 index 000000000..68f4ae5dd --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalanceResult.cpp @@ -0,0 +1,32 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "AutoBalanceResult.h" + +namespace mscl +{ + AutoBalanceResult::AutoBalanceResult(): + m_errorCode(WirelessTypes::autobalance_notComplete), + m_percentAchieved(0), + m_hardwareOffset(0) + { + } + + WirelessTypes::AutoBalanceErrorFlag AutoBalanceResult::errorCode() const + { + return m_errorCode; + } + + float AutoBalanceResult::percentAchieved() const + { + return m_percentAchieved; + } + + uint16 AutoBalanceResult::hardwareOffset() const + { + return m_hardwareOffset; + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalanceResult.h b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalanceResult.h new file mode 100644 index 000000000..8418d7c2a --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalanceResult.h @@ -0,0 +1,63 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +//PUBLIC_HEADER +#pragma once + +#include "mscl/MicroStrain/ByteStream.h" +#include "mscl/MicroStrain/ResponsePattern.h" +#include "mscl/MicroStrain/Wireless/WirelessTypes.h" +#include "mscl/Types.h" + +namespace mscl +{ + //API Class: AutoBalanceResult + // Represents the result from an AutoBalance command. + class AutoBalanceResult + { + friend class AutoBalance_v2; + friend class BaseStation_Impl; + friend class WirelessNode_Impl; + + protected: + //Variable: m_errorCode + // The error code from the response. + WirelessTypes::AutoBalanceErrorFlag m_errorCode; + + //Variable: m_percentAchieved + // The percentage (0 - 100) achieved from the response. + float m_percentAchieved; + + //Variable: m_hardwareOffset + // The new hardware offset from the response. + uint16 m_hardwareOffset; + + public: + //API Default Constructor: AutoBalanceResult + // Creates an empty AutoBalanceResult object. + AutoBalanceResult(); + + //API Function: errorCode + // Gets the from the response. + // + //Returns: + // The from the autobalance response. + WirelessTypes::AutoBalanceErrorFlag errorCode() const; + + //API Function: percentAchieved + // Gets the percentage that the channel was balanced to from the response. + // + //Returns: + // The new sampled channel value after the autobalance. + float percentAchieved() const; + + //API Function: hardwareOffset + // Get the new hardware offset from the response. + // + //Returns: + // The new hardware offset value after the autobalance. + uint16 hardwareOffset() const; + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalance_v2.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalance_v2.cpp new file mode 100644 index 000000000..135ad187e --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalance_v2.cpp @@ -0,0 +1,93 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "AutoBalance_v2.h" +#include "mscl/MicroStrain/Wireless/Packets/WirelessPacket.h" + +namespace mscl +{ + ByteStream AutoBalance_v2::buildCommand(NodeAddress nodeAddress, uint8 channelNumber, float targetPercent) + { + //build the command ByteStream + ByteStream cmd; + cmd.append_uint8(0xAA); //Start of Packet + cmd.append_uint8(0x05); //Delivery Stop Flag + cmd.append_uint8(0x00); //App Data Type + cmd.append_uint16(nodeAddress); //Node address + cmd.append_uint8(0x07); //Payload Length + cmd.append_uint16(0x0065); //Command Id + cmd.append_uint8(channelNumber); //Channel Number + cmd.append_float(targetPercent); //Target Balance Value + + //calculate the checksum of bytes 2-13 + uint16 checksum = cmd.calculateSimpleChecksum(1, 12); + + cmd.append_uint16(checksum); //Checksum + + return cmd; + } + + AutoBalance_v2::Response::Response(NodeAddress nodeAddress, uint8 channelNumber, float targetPercent, std::weak_ptr collector): + ResponsePattern(collector), + m_nodeAddress(nodeAddress), + m_channelNumber(channelNumber), + m_targetPercent(targetPercent) + { + } + + bool AutoBalance_v2::Response::match(const WirelessPacket& packet) + { + WirelessPacket::Payload payload = packet.payload(); + + //check the main bytes of the packet + if(packet.deliveryStopFlags().toByte() != 0x07 || //delivery stop flag + packet.type() != WirelessPacket::packetType_nodeSuccessReply || //app data type + packet.nodeAddress() != m_nodeAddress || //node address + payload.size() != 0x10 || //payload length + payload.read_uint16(0) != 0x0065 || //command id + payload.read_uint8(2) != m_channelNumber || //channel number (echo) + payload.read_float(3) != m_targetPercent //target percent (echo) + ) + { + //failed to match some of the bytes + return false; + } + + //if we made it here, the packet matches the response pattern + + //error code + m_result.m_errorCode = static_cast(payload.read_uint8(7)); + + //sampled value + m_result.m_percentAchieved = payload.read_float(8); + + //hardware offset + m_result.m_hardwareOffset = static_cast(payload.read_uint32(12)); + + switch(m_result.m_errorCode) + { + case WirelessTypes::autobalance_success: + case WirelessTypes::autobalance_maybeInvalid: + m_success = true; + + default: + m_success = false; + } + + //we have fully matched the response + m_fullyMatched = true; + + //notify that the response was matched + m_matchCondition.notify(); + + return true; + } + + const AutoBalanceResult& AutoBalance_v2::Response::result() const + { + return m_result; + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalance_v2.h b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalance_v2.h new file mode 100644 index 000000000..2cafe5915 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoBalance_v2.h @@ -0,0 +1,86 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "mscl/MicroStrain/ByteStream.h" +#include "mscl/MicroStrain/ResponsePattern.h" +#include "mscl/MicroStrain/Wireless/WirelessTypes.h" +#include "mscl/Types.h" +#include "AutoBalanceResult.h" + +namespace mscl +{ + //Class: AutoBalance_v2 + // Contains logic for the Auto Balance Node command (Version 2). + class AutoBalance_v2 + { + private: + AutoBalance_v2(); //default constructor disabled + AutoBalance_v2(const AutoBalance_v2&); //copy constructor disabled + AutoBalance_v2& operator=(const AutoBalance_v2&); //assignment operator disabled + + public: + //Function: buildCommand + // Builds the AutoBalance_v2 command packet. + // + //Parameters: + // nodeAddress - The address of the Node to build the command for. + // channelNumber - The channel number to balance (ch1 = 1, ch8 = 8). + // targetPercent - The target percentage to balance to (0 - 100). + // + //Returns: + // A containing the command packet. + static ByteStream buildCommand(NodeAddress nodeAddress, uint8 channelNumber, float targetPercent); + + //Class: Response + // Handles the response to the LongPing Node command + class Response: public ResponsePattern + { + public: + //Constructor: Response + // Creates a LongPing Response object + // + //Parameters: + // nodeAddress - the node address to check for in the response. + // channelNumber - The channel number to check for in the response. + // targetPercent - The target percentage (0-100) to check for in the response. + // collector - The used to register and unregister the response. + Response(NodeAddress nodeAddress, uint8 channelNumber, float targetPercent, std::weak_ptr collector); + + private: + //Variable: m_nodeAddress + // The node address to look for in the response. + NodeAddress m_nodeAddress; + + //Variable: m_channelNumber + // The channel number to look for in the response. + uint8 m_channelNumber; + + //Variable: m_targetPercent + // The target percentage to look for in the response. + float m_targetPercent; + + //Variable: m_result + // The containing info about the autobalance response. + AutoBalanceResult m_result; + + public: + //Function: match + // Checks if the passed in matches the expected response pattern's bytes + // + //Parameters: + // packet - The in which to try to find the pattern + // + //Returns: + // true if the packet matches a response pattern, false otherwise + virtual bool match(const WirelessPacket& packet) override; + + //Function: result + // Gets the of the command. + const AutoBalanceResult& result() const; + }; + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCal.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCal.cpp index 684b952af..6c80cbe08 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCal.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCal.cpp @@ -12,95 +12,6 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. namespace mscl { - AutoCalResult::AutoCalResult(): - m_completionFlag(WirelessTypes::autocal_notComplete) - { - } - - WirelessTypes::AutoCalCompletionFlag AutoCalResult::completionFlag() const - { - return m_completionFlag; - } - - //===================================================== - //AutoCalResult_shmLink - //===================================================== - AutoCalResult_shmLink::AutoCalResult_shmLink(): - AutoCalResult(), - m_errorFlagCh1(WirelessTypes::autocalError_none), - m_errorFlagCh2(WirelessTypes::autocalError_none), - m_errorFlagCh3(WirelessTypes::autocalError_none), - m_offsetCh1(0.0f), - m_offsetCh2(0.0f), - m_offsetCh3(0.0f), - m_temperature(0.0f) - { - } - - WirelessTypes::AutoCalErrorFlag AutoCalResult_shmLink::errorFlagCh1() const - { - return m_errorFlagCh1; - } - - WirelessTypes::AutoCalErrorFlag AutoCalResult_shmLink::errorFlagCh2() const - { - return m_errorFlagCh2; - } - - WirelessTypes::AutoCalErrorFlag AutoCalResult_shmLink::errorFlagCh3() const - { - return m_errorFlagCh3; - } - - float AutoCalResult_shmLink::offsetCh1() const - { - return m_offsetCh1; - } - - float AutoCalResult_shmLink::offsetCh2() const - { - return m_offsetCh2; - } - - float AutoCalResult_shmLink::offsetCh3() const - { - return m_offsetCh3; - } - - float AutoCalResult_shmLink::temperature() const - { - return m_temperature; - } - - void AutoCalResult_shmLink::parse(const Bytes& autoCalInfo) - { - if(autoCalInfo.size() < 19) - { - assert(false); - return; - } - - typedef WirelessTypes WT; - - DataBuffer data(autoCalInfo); - - //Ch1 error flag and offset - m_errorFlagCh1 = static_cast(data.read_uint8()); - m_offsetCh1 = data.read_float(); - - //Ch2 error flag and offset - m_errorFlagCh2 = static_cast(data.read_uint8()); - m_offsetCh2 = data.read_float(); - - //Ch3 error flag and offset - m_errorFlagCh3 = static_cast(data.read_uint8()); - m_offsetCh3 = data.read_float(); - - //temperature at time of cal - m_temperature = data.read_float(); - } - - //===================================================== //AutoCal //===================================================== @@ -189,6 +100,7 @@ namespace mscl switch(m_model) { case WirelessModels::node_shmLink2: + case WirelessModels::node_shmLink2_cust1: { if(!match_shmLink(packet)) { diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCal.h b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCal.h index 544c604aa..b06278b94 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCal.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCal.h @@ -3,7 +3,6 @@ Copyright(c) 2015 LORD Corporation. All rights reserved. MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. *******************************************************************************/ -//PUBLIC_HEADER #pragma once #include "mscl/Types.h" @@ -15,111 +14,8 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. namespace mscl { - //API Title: AutoCal - class WirelessPacket; - //API Class: AutoCalResult - // Abstract base class for AutoCal result classes. - class AutoCalResult - { - friend class BaseStation_Impl; - - public: - AutoCalResult(); - virtual ~AutoCalResult() {}; - - //API Function: completionFlag - // Gets the of the AutoCal operation result. - WirelessTypes::AutoCalCompletionFlag completionFlag() const; - - protected: - //Function: parse - // Parses the auto cal info bytes sent in the successful response packet. - // - //Parameters: - // autoCalInfo - The bytes from a successful auto cal command. - virtual void parse(const Bytes& autoCalInfo) = 0; - - //Variable: m_completionFlag - // The of the AutoCal operation. - WirelessTypes::AutoCalCompletionFlag m_completionFlag; - }; - - //API Class: AutoCalResult_shmLink - // Holds the result information from an autoCal_shmLink command. - class AutoCalResult_shmLink : public AutoCalResult - { - private: - //Variable: m_errorFlagCh1 - // The for the channel 1 strain sensor. - WirelessTypes::AutoCalErrorFlag m_errorFlagCh1; - - //Variable: m_errorFlagCh2 - // The for the channel 2 strain sensor. - WirelessTypes::AutoCalErrorFlag m_errorFlagCh2; - - //Variable: m_errorFlagCh3 - // The for the channel 3 strain sensor. - WirelessTypes::AutoCalErrorFlag m_errorFlagCh3; - - //Variable: m_offsetCh1 - // The offset applied for the channel 1 strain sensor. - float m_offsetCh1; - - //Variable: m_offsetCh2 - // The offset applied for the channel 2 strain sensor. - float m_offsetCh2; - - //Variable: m_offsetCh3 - // The offset applied for the channel 3 strain sensor. - float m_offsetCh3; - - //Variable: m_temperature - // The temperature at the time of calibration. - float m_temperature; - - public: - AutoCalResult_shmLink(); - virtual ~AutoCalResult_shmLink() {}; - - //API Function: errorFlagCh1 - // Gets the for the channel 1 strain sensor. - WirelessTypes::AutoCalErrorFlag errorFlagCh1() const; - - //API Function: errorFlagCh2 - // Gets the for the channel 2 strain sensor. - WirelessTypes::AutoCalErrorFlag errorFlagCh2() const; - - //API Function: errorFlagCh3 - // Gets the for the channel 3 strain sensor. - WirelessTypes::AutoCalErrorFlag errorFlagCh3() const; - - //API Function: offsetCh1 - // Gets the offset applied for the channel 1 strain sensor. - float offsetCh1() const; - - //API Function: offsetCh2 - // Gets the offset applied for the channel 2 strain sensor. - float offsetCh2() const; - - //API Function: offsetCh3 - // Gets the offset applied for the channel 3 strain sensor. - float offsetCh3() const; - - //API Function: temperature - // Gets the temperature (in °C) at the time of the calibration. - float temperature() const; - - protected: - //Function: parse - // Parses the auto cal info bytes for the shm-link. - virtual void parse(const Bytes& autoCalInfo) final; - }; - - - -#ifndef SWIG //Class: AutoCal // Contains logic for the AutoCal Node command. class AutoCal @@ -245,6 +141,4 @@ namespace mscl bool match_shmLink(const WirelessPacket& packet); }; }; -#endif - } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCalResult.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCalResult.cpp new file mode 100644 index 000000000..b847959b6 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCalResult.cpp @@ -0,0 +1,98 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "AutoCalResult.h" + +namespace mscl +{ + AutoCalResult::AutoCalResult(): + m_completionFlag(WirelessTypes::autocal_notComplete) + { + } + + WirelessTypes::AutoCalCompletionFlag AutoCalResult::completionFlag() const + { + return m_completionFlag; + } + + //===================================================== + //AutoCalResult_shmLink + //===================================================== + AutoCalResult_shmLink::AutoCalResult_shmLink(): + AutoCalResult(), + m_errorFlagCh1(WirelessTypes::autocalError_none), + m_errorFlagCh2(WirelessTypes::autocalError_none), + m_errorFlagCh3(WirelessTypes::autocalError_none), + m_offsetCh1(0.0f), + m_offsetCh2(0.0f), + m_offsetCh3(0.0f), + m_temperature(0.0f) + { + } + + WirelessTypes::AutoCalErrorFlag AutoCalResult_shmLink::errorFlagCh1() const + { + return m_errorFlagCh1; + } + + WirelessTypes::AutoCalErrorFlag AutoCalResult_shmLink::errorFlagCh2() const + { + return m_errorFlagCh2; + } + + WirelessTypes::AutoCalErrorFlag AutoCalResult_shmLink::errorFlagCh3() const + { + return m_errorFlagCh3; + } + + float AutoCalResult_shmLink::offsetCh1() const + { + return m_offsetCh1; + } + + float AutoCalResult_shmLink::offsetCh2() const + { + return m_offsetCh2; + } + + float AutoCalResult_shmLink::offsetCh3() const + { + return m_offsetCh3; + } + + float AutoCalResult_shmLink::temperature() const + { + return m_temperature; + } + + void AutoCalResult_shmLink::parse(const Bytes& autoCalInfo) + { + if(autoCalInfo.size() < 19) + { + assert(false); + return; + } + + typedef WirelessTypes WT; + + DataBuffer data(autoCalInfo); + + //Ch1 error flag and offset + m_errorFlagCh1 = static_cast(data.read_uint8()); + m_offsetCh1 = data.read_float(); + + //Ch2 error flag and offset + m_errorFlagCh2 = static_cast(data.read_uint8()); + m_offsetCh2 = data.read_float(); + + //Ch3 error flag and offset + m_errorFlagCh3 = static_cast(data.read_uint8()); + m_offsetCh3 = data.read_float(); + + //temperature at time of cal + m_temperature = data.read_float(); + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCalResult.h b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCalResult.h new file mode 100644 index 000000000..628739bec --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/AutoCalResult.h @@ -0,0 +1,117 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +//PUBLIC_HEADER +#pragma once + +#include "mscl/Types.h" +#include "mscl/Version.h" +#include "mscl/MicroStrain/ByteStream.h" +#include "mscl/MicroStrain/ResponsePattern.h" +#include "mscl/MicroStrain/Wireless/WirelessModels.h" +#include "mscl/MicroStrain/Wireless/WirelessTypes.h" + +namespace mscl +{ + class WirelessPacket; + + //API Class: AutoCalResult + // Abstract base class for AutoCal result classes. + class AutoCalResult + { + friend class BaseStation_Impl; + + public: + AutoCalResult(); + virtual ~AutoCalResult() {}; + + //API Function: completionFlag + // Gets the of the AutoCal operation result. + WirelessTypes::AutoCalCompletionFlag completionFlag() const; + + protected: + //Function: parse + // Parses the auto cal info bytes sent in the successful response packet. + // + //Parameters: + // autoCalInfo - The bytes from a successful auto cal command. + virtual void parse(const Bytes& autoCalInfo) = 0; + + //Variable: m_completionFlag + // The of the AutoCal operation. + WirelessTypes::AutoCalCompletionFlag m_completionFlag; + }; + + //API Class: AutoCalResult_shmLink + // Holds the result information from an autoCal_shmLink command. + class AutoCalResult_shmLink : public AutoCalResult + { + private: + //Variable: m_errorFlagCh1 + // The for the channel 1 strain sensor. + WirelessTypes::AutoCalErrorFlag m_errorFlagCh1; + + //Variable: m_errorFlagCh2 + // The for the channel 2 strain sensor. + WirelessTypes::AutoCalErrorFlag m_errorFlagCh2; + + //Variable: m_errorFlagCh3 + // The for the channel 3 strain sensor. + WirelessTypes::AutoCalErrorFlag m_errorFlagCh3; + + //Variable: m_offsetCh1 + // The offset applied for the channel 1 strain sensor. + float m_offsetCh1; + + //Variable: m_offsetCh2 + // The offset applied for the channel 2 strain sensor. + float m_offsetCh2; + + //Variable: m_offsetCh3 + // The offset applied for the channel 3 strain sensor. + float m_offsetCh3; + + //Variable: m_temperature + // The temperature at the time of calibration. + float m_temperature; + + public: + AutoCalResult_shmLink(); + virtual ~AutoCalResult_shmLink() {}; + + //API Function: errorFlagCh1 + // Gets the for the channel 1 strain sensor. + WirelessTypes::AutoCalErrorFlag errorFlagCh1() const; + + //API Function: errorFlagCh2 + // Gets the for the channel 2 strain sensor. + WirelessTypes::AutoCalErrorFlag errorFlagCh2() const; + + //API Function: errorFlagCh3 + // Gets the for the channel 3 strain sensor. + WirelessTypes::AutoCalErrorFlag errorFlagCh3() const; + + //API Function: offsetCh1 + // Gets the offset applied for the channel 1 strain sensor. + float offsetCh1() const; + + //API Function: offsetCh2 + // Gets the offset applied for the channel 2 strain sensor. + float offsetCh2() const; + + //API Function: offsetCh3 + // Gets the offset applied for the channel 3 strain sensor. + float offsetCh3() const; + + //API Function: temperature + // Gets the temperature (in °C) at the time of the calibration. + float temperature() const; + + protected: + //Function: parse + // Parses the auto cal info bytes for the shm-link. + virtual void parse(const Bytes& autoCalInfo) final; + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/LongPing.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Commands/LongPing.cpp index a69528623..6232be85f 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Commands/LongPing.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/LongPing.cpp @@ -106,6 +106,8 @@ namespace mscl //notify that the response was matched m_matchCondition.notify(); + m_success = true; + return true; } diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/ReadSingleSensor.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Commands/ReadSingleSensor.cpp new file mode 100644 index 000000000..489b21d12 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/ReadSingleSensor.cpp @@ -0,0 +1,88 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "ReadSingleSensor.h" +#include "mscl/MicroStrain/ChecksumBuilder.h" + +namespace mscl +{ + ByteStream ReadSingleSensor::buildCommand(NodeAddress nodeAddress, uint8 channelNumber) + { + //build the command ByteStream + ByteStream cmd; + cmd.append_uint8(0x03); //Start of Packet + cmd.append_uint16(nodeAddress); //Node address (2 bytes) + cmd.append_uint8(0x01); //Command Byte + cmd.append_uint8(channelNumber); //Channel number + + return cmd; + } + + ReadSingleSensor::Response::Response(std::weak_ptr collector): + ResponsePattern(collector), + m_sensorValue(0) + { + } + + bool ReadSingleSensor::Response::match(DataBuffer& data) + { + const uint16 TOTAL_BYTES = 5; + + //if there aren't enough bytes in the buffer to match the response + if(data.bytesRemaining() < TOTAL_BYTES) + { + //not a good response + m_success = false; + return false; + } + + //create a save point with the data + ReadBufferSavePoint savePoint(&data); + + //verify the command id + if(data.read_uint8() != 0x03) + { + //not a good response + m_success = false; + return false; + } + + uint16 sensorVal = data.read_uint16(); + + ChecksumBuilder checksum; + checksum.append_uint16(sensorVal); //value of the requested channel + + //verify the checksum (only a checksum on the actual data value) + if(checksum.simpleChecksum() != data.read_uint16()) + { + //not a good response + m_success = false; + return false; + } + + //if we made it this far, the bytes match the expected response + + m_success = true; + + m_sensorValue = sensorVal; + + //commit the current read position + savePoint.commit(); + + //we have fully matched the response + m_fullyMatched = true; + + //notify that the response was matched + m_matchCondition.notify(); + + return true; + } + + uint16 ReadSingleSensor::Response::sensorValue() const + { + return m_sensorValue; + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/ReadSingleSensor.h b/MSCL/source/mscl/MicroStrain/Wireless/Commands/ReadSingleSensor.h new file mode 100644 index 000000000..66ba4fe48 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/ReadSingleSensor.h @@ -0,0 +1,72 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "mscl/MicroStrain/ByteStream.h" +#include "mscl/MicroStrain/ResponsePattern.h" +#include "mscl/Types.h" + +namespace mscl +{ + +#ifndef SWIG + + //Class: ReadSingleSensor + // Contains logic for the Read Single Sensor Node command + class ReadSingleSensor + { + private: + ReadSingleSensor(); //default constructor disabled + ReadSingleSensor(const ReadSingleSensor&); //copy constructor disabled + ReadSingleSensor& operator=(const ReadSingleSensor&); //assignment operator disabled + + public: + //Function: buildCommand + // Builds the ReadSingleSensor command packet. + // + //Parameters: + // nodeAddress - The address of the Node to build the command for. + // + //Returns: + // A containing the command packet. + static ByteStream buildCommand(NodeAddress nodeAddress, uint8 channelNumber); + + //Class: Response + // Handles the response to the ReadSingleSensor node command + class Response : public ResponsePattern + { + private: + //Variable: m_sensorValue + // The value read from the sensor. + uint16 m_sensorValue; + + public: + //Constructor: Response + // Creates a ReadSingleSensor Response object + // + //Parameters: + // collector - The used to register and unregister the response + explicit Response(std::weak_ptr collector); + + public: + //Function: match + // Checks if the bytes passed in match the response pattern from their current read position + // + //Parameters: + // data - The containing the bytes in which to try to find the pattern + // + //Returns: + // true if the response pattern was found, false otherwise + virtual bool match(DataBuffer& data) override; + + //Function: sensorValue + // Gets the sensor value that was in the response to the read single sensor command. + uint16 sensorValue() const; + }; + }; + +#endif +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/ShortPing_v2.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Commands/ShortPing_v2.cpp new file mode 100644 index 000000000..d6b1ba06e --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/ShortPing_v2.cpp @@ -0,0 +1,106 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "ShortPing_v2.h" +#include "mscl/MicroStrain/Wireless/Packets/WirelessPacket.h" + +namespace mscl +{ + ByteStream ShortPing_v2::buildCommand(NodeAddress nodeAddress) + { + //build the command ByteStream + ByteStream cmd; + cmd.append_uint8(0xAA); //Start of Packet + cmd.append_uint8(0x0E); //Delivery Stop Flag + cmd.append_uint8(0x00); //App Data Type + cmd.append_uint16(nodeAddress); //Node address (2 bytes) + cmd.append_uint8(0x02); //Payload length + cmd.append_uint16(0x12); //Command ID (2 bytes) + + //calculate the checksum of bytes 2-8 + uint16 checksum = cmd.calculateSimpleChecksum(1, 7); + + cmd.append_uint16(checksum); //Checksum (2 bytes) + + return cmd; + } + + ShortPing_v2::Response::Response(NodeAddress nodeAddress, std::weak_ptr collector): + ResponsePattern(collector), + m_nodeAddress(nodeAddress) + { + } + + bool ShortPing_v2::Response::matchSuccessResponse(const WirelessPacket& packet) + { + WirelessPacket::Payload payload = packet.payload(); + + //check the main bytes of the packet + if(packet.deliveryStopFlags().toByte() != 0x07 || //delivery stop flag + packet.type() != WirelessPacket::packetType_nodeSuccessReply || //app data type + packet.nodeAddress() != m_nodeAddress || //node address + payload.size() != 0x02 || //payload length + payload.read_uint16(0) != 0x0012 //command ID + ) + { + //failed to match some of the bytes + return false; + } + + m_success = true; + + return true; + } + + bool ShortPing_v2::Response::matchFailResponse(const WirelessPacket& packet) + { + WirelessPacket::Payload payload = packet.payload(); + + //check the main bytes of the packet + if(packet.deliveryStopFlags().toByte() != 0x07 || //delivery stop flag + packet.type() != WirelessPacket::packetType_nodeErrorReply || //app data type + packet.nodeAddress() != m_nodeAddress || //node address + payload.size() != 0x02 || //payload length + payload.read_uint16(0) != 0x0012 //command ID + ) + { + //failed to match some of the bytes + return false; + } + + //set the result to failure + m_success = false; + + return true; + } + + bool ShortPing_v2::Response::match(const WirelessPacket& packet) + { + //if the bytes match the success response + if(matchSuccessResponse(packet)) + { + //we have fully matched the response + m_fullyMatched = true; + + //notify that the response was matched + m_matchCondition.notify(); + return true; + } + //if the bytes match the fail response + else if(matchFailResponse(packet)) + { + //we have fully matched the response + m_fullyMatched = true; + + //notify that the response was matched + m_matchCondition.notify(); + return true; + } + + //the bytes don't match any response + return false; + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/ShortPing_v2.h b/MSCL/source/mscl/MicroStrain/Wireless/Commands/ShortPing_v2.h new file mode 100644 index 000000000..fce857a83 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/ShortPing_v2.h @@ -0,0 +1,86 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "mscl/MicroStrain/ByteStream.h" +#include "mscl/MicroStrain/ResponsePattern.h" + +namespace mscl +{ + class WirelessPacket; + + //Class: ShortPing_v2 + // Contains logic for the ShortPing Node command (version 2). + class ShortPing_v2 + { + private: + ShortPing_v2(); //default constructor disabled + ShortPing_v2(const ShortPing_v2&); //copy constructor disabled + ShortPing_v2& operator=(const ShortPing_v2&); //assignment operator disabled + + public: + //Function: buildCommand + // Builds the ShortPing_v2 command packet + // + //Parameters: + // nodeAddress - the address of the Node to build the command for. + // + //Returns: + // A containing the ShortPing_v2 command packet. + static ByteStream buildCommand(NodeAddress nodeAddress); + + //Class: Response + // Handles the response to the ShortPing_v2 Node command. + class Response : public ResponsePattern + { + public: + //Constructor: Response + // Creates a ShortPing_v2 Response object. + // + //Parameters: + // nodeAddress - the node address to check for. + // collector - The used to register and unregister the response. + Response(NodeAddress nodeAddress, std::weak_ptr collector); + + private: + //Variable: m_nodeAddress + // The node address to look for in the response + NodeAddress m_nodeAddress; + + public: + //Function: match + // Checks if the passed in matches the expected response pattern's bytes + // + //Parameters: + // packet - The in which to try to find the pattern + // + //Returns: + // true if the packet matches a response pattern, false otherwise + virtual bool match(const WirelessPacket& packet) override; + + private: + //Function: matchSuccessResponse + // Checks if the packet passed in matches the success response. + // + //Parameters: + // packet - The to try to match. + // + //Returns: + // true if the success response pattern was found, false otherwise + bool matchSuccessResponse(const WirelessPacket& packet); + + //Function: matchFailResponse + // Checks if the packet passed in matches the failure response. + // + //Parameters: + // packet - The to try to match. + // + //Returns: + // true if the failure response pattern was found, false otherwise + bool matchFailResponse(const WirelessPacket& packet); + }; + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/WirelessProtocol.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Commands/WirelessProtocol.cpp index 069caebd5..60e3a7cb5 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Commands/WirelessProtocol.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/WirelessProtocol.cpp @@ -13,6 +13,41 @@ namespace mscl { } + std::unique_ptr WirelessProtocol::chooseBaseStationProtocol(const Version& fwVersion) + { + //the BaseStation min fw version for each protocol + static const Version MIN_FW_PROTOCOL_1_1(4, 0); + + if(fwVersion >= MIN_FW_PROTOCOL_1_1) + { + return v1_1(); + } + else + { + return v1_0(); + } + } + + std::unique_ptr WirelessProtocol::chooseNodeProtocol(const Version& fwVersion) + { + //the Node min fw version for each protocol + static const Version MIN_FW_PROTOCOL_1_2(10, 0); + static const Version MIN_FW_PROTOCOL_1_1(8, 21); + + if(fwVersion >= MIN_FW_PROTOCOL_1_2) + { + return v1_2(); + } + else if(fwVersion >= MIN_FW_PROTOCOL_1_1) + { + return v1_1(); + } + else + { + return v1_0(); + } + } + std::unique_ptr WirelessProtocol::v1_0() { std::unique_ptr result(new WirelessProtocol()); @@ -25,16 +60,20 @@ namespace mscl result->m_beaconStatus = nullptr; //Node Commands + result->m_shortPing = std::mem_fn(&BaseStation_Impl::node_shortPing_v1); result->m_readNodeEeprom = std::mem_fn(&BaseStation_Impl::node_readEeprom_v1); result->m_writeNodeEeprom = std::mem_fn(&BaseStation_Impl::node_writeEeprom_v1); result->m_pageDownload = std::mem_fn(&BaseStation_Impl::node_pageDownload_v1); + result->m_autoBalance = std::mem_fn(&BaseStation_Impl::node_autoBalance_v1); return result; } std::unique_ptr WirelessProtocol::v1_1() { - std::unique_ptr result(new WirelessProtocol()); + std::unique_ptr result = WirelessProtocol::v1_0(); + + //changes from v1.0 //BaseStation Commands result->m_pingBase = std::mem_fn(&BaseStation_Impl::ping_v2); @@ -46,7 +85,17 @@ namespace mscl //Node Commands result->m_readNodeEeprom = std::mem_fn(&BaseStation_Impl::node_readEeprom_v2); result->m_writeNodeEeprom = std::mem_fn(&BaseStation_Impl::node_writeEeprom_v2); - result->m_pageDownload = std::mem_fn(&BaseStation_Impl::node_pageDownload_v1); + + return result; + } + + std::unique_ptr WirelessProtocol::v1_2() + { + std::unique_ptr result = WirelessProtocol::v1_1(); + + //changes from v1.1 + result->m_shortPing = std::mem_fn(&BaseStation_Impl::node_shortPing_v2); + result->m_autoBalance = std::mem_fn(&BaseStation_Impl::node_autoBalance_v2); return result; } diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Commands/WirelessProtocol.h b/MSCL/source/mscl/MicroStrain/Wireless/Commands/WirelessProtocol.h index 1616acaf6..54de12290 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Commands/WirelessProtocol.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Commands/WirelessProtocol.h @@ -8,6 +8,7 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #include #include #include "mscl/Timestamp.h" +#include "AutoBalanceResult.h" #include "BaseStation_BeaconStatus.h" namespace mscl @@ -47,6 +48,10 @@ namespace mscl // The function pointer for the Beacon Status protocol command. std::function m_beaconStatus; + //Variable: m_shortPing + // The function pointer for the Short Ping Node protocol command. + std::function m_shortPing; + //Variable: m_readNodeEeprom // The function pointer for the Read Node Eeprom protocol command. std::function m_readNodeEeprom; @@ -59,11 +64,29 @@ namespace mscl // The function pointer for the Node Page Download protocol command. std::function m_pageDownload; + //Variable: m_autoBalance + // The function pointer for the Node AutoBalance protocol command. + std::function m_autoBalance; + public: //Constant: BASE_STATION_ADDRESS // The address of our generic Base Station. static const uint16 BASE_STATION_ADDRESS = 0x1234; + //Function: chooseBaseStationProtocol + // Returns the correct protocol version based on the Base Station's firmware vesrion. + // + //Parameters: + // fwVersion - The firmware version of the Base Station. + static std::unique_ptr chooseBaseStationProtocol(const Version& fwVersion); + + //Function: chooseBaseStationProtocol + // Returns the correct protocol version based on the Wireless Node's firmware vesrion. + // + //Parameters: + // fwVersion - The firmware version of the Node. + static std::unique_ptr chooseNodeProtocol(const Version& fwVersion); + //Function: v1_0 // Static function to create a WirelessProtocol with version 1.0. static std::unique_ptr v1_0(); @@ -71,5 +94,9 @@ namespace mscl //Function: v1_1 // Static function to create a WirelessProtocol with version 1.1. static std::unique_ptr v1_1(); + + //Function: v1_2 + // Static function to create a WirelessProtocol with version 1.2. + static std::unique_ptr v1_2(); }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/ActivitySense.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/ActivitySense.cpp new file mode 100644 index 000000000..d02483b27 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/ActivitySense.cpp @@ -0,0 +1,70 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" + +#include "ActivitySense.h" + +namespace mscl +{ + ActivitySense::ActivitySense(): + m_enabled(false), + m_activityThreshold(0.0), + m_inactivityThreshold(0.0), + m_activityTime(0.0), + m_inactivityTimeout(0.0) + { + } + + bool ActivitySense::enabled() const + { + return m_enabled; + } + + void ActivitySense::enabled(bool enable) + { + m_enabled = enable; + } + + float ActivitySense::activityThreshold() const + { + return m_activityThreshold; + } + + void ActivitySense::activityThreshold(float threshold) + { + m_activityThreshold = threshold; + } + + float ActivitySense::inactivityThreshold() const + { + return m_inactivityThreshold; + } + + void ActivitySense::inactivityThreshold(float threshold) + { + m_inactivityThreshold = threshold; + } + + float ActivitySense::activityTime() const + { + return m_activityTime; + } + + void ActivitySense::activityTime(float time) + { + m_activityTime = time; + } + + float ActivitySense::inactivityTimeout() const + { + return m_inactivityTimeout; + } + + void ActivitySense::inactivityTimeout(float timeout) + { + m_inactivityTimeout = timeout; + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/ActivitySense.h b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/ActivitySense.h new file mode 100644 index 000000000..99e39a78d --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/ActivitySense.h @@ -0,0 +1,125 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +//PUBLIC_HEADER +#pragma once + +#include "mscl/Types.h" + +namespace mscl +{ + //API Class: ActivitySense + // Contains all of the ActivitySense options that can be configured for a WirelessNode. + // Activity Sense is a power saving feature that allows a Node to be in a low-power state when + // no activity is suspected, and then immediately jump to its normal sampling state when a + // certain activity threshold is reached. + class ActivitySense + { + public: + //API Default Constructor: ActivitySense + // Creates a default constructed ActivitySense object. + ActivitySense(); + + private: + //Variable: m_enabled + // Whether Activity Sense is enabled or disabled. + bool m_enabled; + + //Variable: m_activityThreshold + // The activity threshold (in G's). + float m_activityThreshold; + + //Variable: m_inactivityThreshold + // The inactivity threshold (in G's). + float m_inactivityThreshold; + + //Variable: m_activityTime + // The activity time (in seconds). + float m_activityTime; + + //Variable: m_inactivityTimeout + // The inactivity timeout (in seconds). + float m_inactivityTimeout; + + public: + //API Function: enabled + // Gets whether Activity Sense is enabled or disabled in this options object. + // + //Returns: + // true if Activity Sense is enabled in this options object, false if it is disabled. + bool enabled() const; + + //API function: enabled + // Sets whether Activity Sense is enabled or disabled in this options object. + // + //Parameters: + // enable - Whether to enable (true) or disable (false) Activity Sense mode in this options object. + void enabled(bool enable); + + //API Function: activityThreshold + // Gets the current activity threshold value in this options object. + // This is the threshold the channel must exceed, for seconds to begin sampling. + // + //Returns: + // The activity threshold value (in G's) set in this options object. + float activityThreshold() const; + + //API function: activityThreshold + // Sets the activity threshold value in this options object. + // This is the threshold the channel must exceed, for seconds to begin sampling. + // + //Parameters: + // threshold - The activity threshold value (in G's) to set in this options object. + void activityThreshold(float threshold); + + //API Function: inactivityThreshold + // Gets the current inactivity threshold value in this options object. + // This is the threshold the channel must drop below, for seconds to begin sampling. + // + //Returns: + // The inactivity threshold value (in G's) set in this options object. + float inactivityThreshold() const; + + //API function: inactivityThreshold + // Sets the inactivity threshold value in this options object. + // This is the threshold the channel must drop below, for seconds to begin sampling. + // + //Parameters: + // threshold - The inactivity threshold value (in G's) to set in this options object. + void inactivityThreshold(float threshold); + + //API Function: activityTime + // Gets the amount of time that activity must be seen above before the Node + // enters its sampling mode, currently set in this options object. + // + //Returns: + // The activity time value set in this options object. + float activityTime() const; + + //API function: activityTime + // Sets the amount of time that activity must be seen above before the Node + // enters its sampling mode, in this options object. + // + //Parameters: + // time - The activity time value to set in this options object. + void activityTime(float time); + + //API Function: inactivityTimeout + // Gets the current amount of time that the Activity Sense mode runs without a value over the + // before it goes back into a low power mode, in this options object. + // + //Returns: + // The inactivity timeout value set in this options object. + float inactivityTimeout() const; + + //API function: inactivityTimeout + // Sets the current amount of time that the Activity Sense mode runs without a value over the + // before it goes back into a low power mode, in this options object. + // + //Parameters: + // timeout - The inactivity timeout value to set in this options object. + void inactivityTimeout(float timeout); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/BaseStationEepromHelper.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/BaseStationEepromHelper.cpp index e29de9afe..2306fca27 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/BaseStationEepromHelper.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/BaseStationEepromHelper.cpp @@ -38,14 +38,37 @@ namespace mscl WirelessTypes::TransmitPower BaseStationEepromHelper::read_transmitPower() const { - //read and return the transmit power level - return static_cast(read(BaseStationEepromMap::TX_POWER_LEVEL).as_uint16()); + int16 val = read(BaseStationEepromMap::TX_POWER_LEVEL).as_int16(); + + if(m_baseStation->features().supportsNewTransmitPowers()) + { + return static_cast(val); + } + else + { + //legacy value, convert to current value before returning + + //read and return the transmit power level + return WirelessTypes::legacyToTransmitPower(static_cast(val)); + } } void BaseStationEepromHelper::write_transmitPower(WirelessTypes::TransmitPower power) { + int16 valToWrite = 0; + + if(m_baseStation->features().supportsNewTransmitPowers()) + { + valToWrite = static_cast(power); + } + else + { + //need to write the legacy value for the device to understand it + valToWrite = static_cast(WirelessTypes::transmitPowerToLegacy(power)); + } + //write the transmit power level to the node - write(BaseStationEepromMap::TX_POWER_LEVEL, Value::UINT16(static_cast(power))); + write(BaseStationEepromMap::TX_POWER_LEVEL, Value(valueType_int16, valToWrite)); } BaseStationButton BaseStationEepromHelper::read_button(uint8 buttonNumber, BaseStationButton::UserAction action) const @@ -187,7 +210,15 @@ namespace mscl //write all the values to eeprom write(analogEE_nodeAddress, Value::UINT16(pair.nodeAddress())); - write(analogEE_nodeChannel, Value::UINT16(static_cast(pair.nodeChannel()))); + + //a value of 0xFF should disable the channel (actually write a 0xFFFF) + uint16 chToWrite = pair.nodeChannel(); + if(chToWrite == 0xFF) + { + chToWrite = 0xFFFF; + } + write(analogEE_nodeChannel, Value::UINT16(chToWrite)); + write(analogEE_maxFloat, Value::FLOAT(pair.outputVal_3V())); write(analogEE_minFloat, Value::FLOAT(pair.outputVal_0V())); } diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/BaseStationEepromMap.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/BaseStationEepromMap.cpp index d834d8898..223c3f893 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/BaseStationEepromMap.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/BaseStationEepromMap.cpp @@ -16,7 +16,7 @@ namespace mscl const EepromLocation BaseStationEepromMap::MODEL_NUMBER (46, valueType_uint16); const EepromLocation BaseStationEepromMap::MODEL_OPTION (48, valueType_uint16); const EepromLocation BaseStationEepromMap::FREQUENCY (90, valueType_uint16); - const EepromLocation BaseStationEepromMap::TX_POWER_LEVEL (94, valueType_uint16); + const EepromLocation BaseStationEepromMap::TX_POWER_LEVEL (94, valueType_int16); const EepromLocation BaseStationEepromMap::BEACON_SOURCE (96, valueType_uint16); const EepromLocation BaseStationEepromMap::FIRMWARE_VER (108, valueType_uint16); const EepromLocation BaseStationEepromMap::FIRMWARE_VER2 (110, valueType_uint16); diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/ConfigIssue.h b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/ConfigIssue.h index d0eed2e02..0a2d683c1 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/ConfigIssue.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/ConfigIssue.h @@ -40,8 +40,16 @@ namespace mscl // CONFIG_TRANSMIT_POWER - 17 - Transmit Power // CONFIG_LINEAR_EQUATION - 18 - Linear Equation // CONFIG_FATIGUE - 19 - Fatigue Options - // CONFIG_HISTOGRAM - 20 - Histogram Options - // CONFIG_HARDWARE_OFFSET - 21 - Hardware Offset + // CONFIG_FATIGUE_MODE - 20 - Fatigue Options - Fatigue Mode + // CONFIG_FATIGUE_ANGLE_ID - 21 - Fatigue Options - Angle ID + // CONFIG_FATIGUE_SN_CURVE - 22 - Fatigue Options - SN Curve Segment + // CONFIG_FATIGUE_DIST_NUM_ANGLES - 23 - Fatigue Options - Number of Distributed Angles + // CONFIG_FATIGUE_DIST_ANGLE - 24 - Fatigue Options - Low/Upper Distributed Angle + // CONFIG_HISTOGRAM - 25 - Histogram Options + // CONFIG_HISTOGRAM_TX_RATE - 26 - Histogram Transmit Rate + // CONFIG_HARDWARE_OFFSET - 27 - Hardware Offset + // CONFIG_ACTIVITY_SENSE - 28 - Activity Sense + // CONFIG_GAUGE_FACTOR - 29 - Gauge Factor enum ConfigOption { CONFIG_SAMPLING_MODE = 0, @@ -64,8 +72,16 @@ namespace mscl CONFIG_TRANSMIT_POWER = 17, CONFIG_LINEAR_EQUATION = 18, CONFIG_FATIGUE = 19, - CONFIG_HISTOGRAM = 20, - CONFIG_HARDWARE_OFFSET = 21 + CONFIG_FATIGUE_MODE = 20, + CONFIG_FATIGUE_ANGLE_ID = 21, + CONFIG_FATIGUE_SN_CURVE = 22, + CONFIG_FATIGUE_DIST_NUM_ANGLES = 23, + CONFIG_FATIGUE_DIST_ANGLE = 24, + CONFIG_HISTOGRAM = 25, + CONFIG_HISTOGRAM_TX_RATE = 26, + CONFIG_HARDWARE_OFFSET = 27, + CONFIG_ACTIVITY_SENSE = 28, + CONFIG_GAUGE_FACTOR = 29 }; ConfigIssue(); //default constructor diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/Eeprom.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/Eeprom.cpp index 74425d85e..b92cc868d 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/Eeprom.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/Eeprom.cpp @@ -104,6 +104,9 @@ namespace mscl case valueType_uint32: return Value(type, readEeprom_uint32(eepromLoc)); + case valueType_int16: + return Value(type, readEeprom_int16(eepromLoc)); + default: assert(false); //we are trying to read a value with an invalid type? return Value(type, readEeprom(eepromLoc)); //just default to uint16 @@ -131,6 +134,10 @@ namespace mscl writeEeprom_uint32(eepromLoc, val.as_uint32()); break; + case valueType_int16: + writeEeprom_int16(eepromLoc, val.as_int16()); + break; + default: assert(false); //we are trying to write a value with an invalid type? writeEeprom(eepromLoc, val.as_uint16()); //just default to uint16 @@ -166,19 +173,9 @@ namespace mscl return Utils::make_uint32(msw, lsw); } - uint16 Eeprom::readEeprom_uint16(EepromLocation location) - { - return readEeprom(location.location()); - } - - float Eeprom::readEeprom_float(EepromLocation location) - { - return readEeprom_float(location.location()); - } - - uint32 Eeprom::readEeprom_uint32(EepromLocation location) + int16 Eeprom::readEeprom_int16(uint16 location) { - return readEeprom_uint32(location.location()); + return static_cast(readEeprom(location)); } void Eeprom::writeEeprom_float(uint16 location, float value) @@ -195,16 +192,6 @@ namespace mscl writeEeprom(location + 2, Utils::make_uint16(b3, b4)); //TODO: possibly throw a custom exception if this throws? We wrote the msw but not the lsw } - void Eeprom::writeEeprom_uint16(EepromLocation location, uint16 value) - { - writeEeprom(location.location(), value); - } - - void Eeprom::writeEeprom_float(EepromLocation location, float value) - { - writeEeprom_float(location.location(), value); - } - void Eeprom::writeEeprom_uint32(uint16 location, uint32 value) { uint16 msw = 0; @@ -219,4 +206,9 @@ namespace mscl //try to write the lsw writeEeprom(location + 2, lsw); //TODO: possibly throw a custom exception if this throws? We wrote the msw but not the lsw } + + void Eeprom::writeEeprom_int16(uint16 location, int16 value) + { + writeEeprom(location, static_cast(value)); + } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/Eeprom.h b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/Eeprom.h index 5ce242147..8d1076b63 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/Eeprom.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/Eeprom.h @@ -176,6 +176,7 @@ namespace mscl // - : A connection error has occurred with the BaseStation. void writeEeprom(const EepromLocation& location, const Value& val); + private: //Function: readEeprom_float // Attempts to read 2 eeprom values from a device and build them into a float. // If caching is enabled and there is a previously cached value available, this will @@ -212,49 +213,13 @@ namespace mscl // - : A connection error has occurred with the BaseStation. virtual uint32 readEeprom_uint32(uint16 location); - //Function: readEeprom - // Attempts to read an eeprom value from a device. + //Function: readEeprom_int16 + // Attempts to read an eeprom value from a device as a signed int16. // If caching is enabled and there is a previously cached value available, this will // just return the value from the cache and will not communicate with the device. // //Parameters: - // location - The to read from the device and update in the cache. - // - //Returns: - // The eeprom value for the requested location. - // - //Exceptions: - // - : Unsupported eeprom location. - // - : Failed to read the value from the BaseStation. - // - : Failed to read the value from the Node. - // - : A connection error has occurred with the BaseStation. - virtual uint16 readEeprom_uint16(EepromLocation location); - - //Function: readEeprom_float - // Attempts to read 2 eeprom values from a device and build them into a float. - // If caching is enabled and there is a previously cached value available, this will - // just return the value from the cache and will not communicate with the device. - // - //Parameters: - // location - The to read from the device and update in the cache. - // - //Returns: - // The eeprom value for the requested location. - // - //Exceptions: - // - : Unsupported eeprom location. - // - : Failed to read the value from the BaseStation. - // - : Failed to read the value from the Node. - // - : A connection error has occurred with the BaseStation. - virtual float readEeprom_float(EepromLocation location); - - //Function: readEeprom_uint32 - // Attempts to read 2 eeprom values from a device and build them into a uint32. - // If caching is enabled and there is a previously cached value available, this will - // just return the value from the cache and will not communicate with the device. - // - //Parameters: - // location - The to read from the device and update in the cache. + // location - The eeprom location to read from the device and update in the cache. // //Returns: // The eeprom value for the requested location. @@ -264,7 +229,7 @@ namespace mscl // - : Failed to read the value from the BaseStation. // - : Failed to read the value from the Node. // - : A connection error has occurred with the BaseStation. - virtual uint32 readEeprom_uint32(EepromLocation location); + virtual int16 readEeprom_int16(uint16 location); //Function: writeEeprom_float // Attempts to write 2 eeprom values to a device as a float. @@ -277,27 +242,13 @@ namespace mscl // value - The value to write to the eeprom on the device and update in the cache. // //Exceptions: + // - : Unsupported eeprom location or value. // - : Failed to write the value to the Node. // - : A connection error has occurred with the BaseStation. virtual void writeEeprom_float(uint16 location, float value); - //Function: writeEeprom - // Attempts to write an eeprom value to a device. - // If successful, the cache will be updated with the changed value as well. - // If caching is enabled and the value in the cache is the same as that attempting to be written, - // nothing will be written to the device and this function will have no affect. - // - //Parameters: - // location - The to write to on the device and update in the cache. - // value - The value to write to the eeprom on the device and update in the cache. - // - //Exceptions: - // - : Failed to write the value to the Node. - // - : A connection error has occurred with the BaseStation. - virtual void writeEeprom_uint16(EepromLocation location, uint16 value); - - //Function: writeEeprom_float - // Attempts to write 2 eeprom values to a device as a float. + //Function: writeEeprom_uint32 + // Attempts to write 2 eeprom values to a device as a uint32. // If successful, the cache will be updated with the changed value as well. // If caching is enabled and the value in the cache is the same as that attempting to be written, // nothing will be written to the device and this function will have no affect. @@ -307,23 +258,25 @@ namespace mscl // value - The value to write to the eeprom on the device and update in the cache. // //Exceptions: + // - : Unsupported eeprom location or value. // - : Failed to write the value to the Node. // - : A connection error has occurred with the BaseStation. - virtual void writeEeprom_float(EepromLocation location, float value); + virtual void writeEeprom_uint32(uint16 location, uint32 value); - //Function: writeEeprom - // Attempts to write 2 eeprom values to a device as a uint32. + //Function: writeEeprom_int16 + // Attempts to write an eeprom value to a device from a signed int16. // If successful, the cache will be updated with the changed value as well. // If caching is enabled and the value in the cache is the same as that attempting to be written, // nothing will be written to the device and this function will have no affect. // //Parameters: - // location - The to write to on the device and update in the cache. + // location - The eeprom location to write to on the device and update in the cache. // value - The value to write to the eeprom on the device and update in the cache. // //Exceptions: + // - : Unsupported eeprom location or value. // - : Failed to write the value to the Node. // - : A connection error has occurred with the BaseStation. - virtual void writeEeprom_uint32(uint16 location, uint32 value); + virtual void writeEeprom_int16(uint16 location, int16 value); }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/FatigueOptions.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/FatigueOptions.cpp index 65e30005b..a1980b788 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/FatigueOptions.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/FatigueOptions.cpp @@ -47,7 +47,12 @@ namespace mscl m_youngsModulus(0.2025f), m_poissonsRatio(0.3f), m_peakValleyThreshold(0), - m_rawMode(false) + m_debugMode(false), + m_fatigueMode(WirelessTypes::fatigueMode_angleStrain), + m_distMode_numAngles(0), + m_distMode_lowerBound(0.0f), + m_distMode_upperBound(1.0f), + m_histogramEnable(true) { } @@ -81,14 +86,14 @@ namespace mscl m_peakValleyThreshold = val; } - bool FatigueOptions::rawMode() const + bool FatigueOptions::debugMode() const { - return m_rawMode; + return m_debugMode; } - void FatigueOptions::rawMode(bool enable) + void FatigueOptions::debugMode(bool enable) { - m_rawMode = enable; + m_debugMode = enable; } float FatigueOptions::damageAngle(uint8 angleId) const @@ -141,4 +146,54 @@ namespace mscl { m_snCurveSegments[segmentId] = segment; } + + WirelessTypes::FatigueMode FatigueOptions::fatigueMode() const + { + return m_fatigueMode; + } + + void FatigueOptions::fatigueMode(WirelessTypes::FatigueMode mode) + { + m_fatigueMode = mode; + } + + uint8 FatigueOptions::distributedAngleMode_numAngles() const + { + return m_distMode_numAngles; + } + + void FatigueOptions::distributedAngleMode_numAngles(uint8 numAngles) + { + m_distMode_numAngles = numAngles; + } + + float FatigueOptions::distributedAngleMode_lowerBound() const + { + return m_distMode_lowerBound; + } + + void FatigueOptions::distributedAngleMode_lowerBound(float angle) + { + m_distMode_lowerBound = angle; + } + + float FatigueOptions::distributedAngleMode_upperBound() const + { + return m_distMode_upperBound; + } + + void FatigueOptions::distributedAngleMode_upperBound(float angle) + { + m_distMode_upperBound = angle; + } + + bool FatigueOptions::histogramEnable() const + { + return m_histogramEnable; + } + + void FatigueOptions::histogramEnable(bool enable) + { + m_histogramEnable = enable; + } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/FatigueOptions.h b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/FatigueOptions.h index 5d3c9a789..bc0023793 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/FatigueOptions.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/FatigueOptions.h @@ -7,6 +7,7 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #pragma once #include +#include "mscl/MicroStrain/Wireless/WirelessTypes.h" #include "mscl/Types.h" namespace mscl @@ -93,9 +94,9 @@ namespace mscl // The peak/valley threshold. uint16 m_peakValleyThreshold; - //Variable: m_rawMode + //Variable: m_debugMode // Whether raw data is enabled or disabled. - bool m_rawMode; + bool m_debugMode; //Variable: m_damageAngles // The . @@ -105,6 +106,26 @@ namespace mscl // The . SnCurveSegments m_snCurveSegments; + //Variable: m_fatigueMode + // Whether distributed angle mode is enabled or disabled. + WirelessTypes::FatigueMode m_fatigueMode; + + //Variable: m_distMode_numAngles + // The number of angles (4 - 16) to use in distributed angle mode. + uint8 m_distMode_numAngles; + + //Variable: m_distMode_lowerBound + // The lower bound angle when using the distributed angle mode. + float m_distMode_lowerBound; + + //Variable: m_distMode_upperBound + // The upper bound angle when using the distributed angle mode. + float m_distMode_upperBound; + + //Variable: m_histogramEnable + // Whether histograms are enabled or disabled. + bool m_histogramEnable; + public: //API Function: youngsModulus // Gets the Young's Modulus set in this options object. @@ -139,17 +160,18 @@ namespace mscl // val - The Peak/Valley Threshold to set. void peakValleyThreshold(uint16 val); - //API Function: rawMode - // Gets the raw mode flag set in this options object. - // This determines whether raw data that builds the Histograms will be sent when sampling. - bool rawMode() const; + //API Function: debugMode + // Gets the debug mode flag set in this options object. + // This determines whether raw angle data that builds the Histograms will be sent when sampling. + bool debugMode() const; - //API Function: rawMode - // Sets the raw mode flag in this options object. + //API Function: debugMode + // Sets the debug mode flag in this options object. + // This determines whether raw angle data that builds the Histograms will be sent when sampling. // //Parameters: - // enable - Whether to enable (true) or disable (false) raw mode. - void rawMode(bool enable); + // enable - Whether to enable (true) or disable (false) debug mode. + void debugMode(bool enable); //API Function: damageAngle // Gets the damage angle set in this options object, for the given angle id (0-based). @@ -195,5 +217,70 @@ namespace mscl // segmentId - The segment ID to set the segment for. // segment - The to set. void snCurveSegment(uint8 segmentId, const SnCurveSegment& segment); + + //API Function: fatigueMode + // The that is set in this options object. + WirelessTypes::FatigueMode fatigueMode() const; + + //API Function: distributedAngleMode_enabled + // Sets whether distributed angle mode is enabled or disabled in this options object. + // Distributed Angle Mode allows the user to enable an even distribution of 4-16 angles. + // When in this mode, the standard will not be used by the Node. + // + //Parameters: + // enable - Whether to enable or disable distributed angle mode. + void fatigueMode(WirelessTypes::FatigueMode mode); + + //API Function: distributedAngleMode_numAngles + // Gets the current number of angles to use for distributed angle mode in this options object. + // Note: The Node will only use this if the is set to distributed angle mode. + uint8 distributedAngleMode_numAngles() const; + + //API Function: distributedAngleMode_numAngles + // Sets the current number of angles to use for distributed angle mode in this options object. + // Note: Note: The Node will only use this if the is set to distributed angle mode. + // + //Parameters: + // numAngles - The number of angles to use (4-16). + void distributedAngleMode_numAngles(uint8 numAngles); + + //API Function: distributedAngleMode_lowerBound + // Gets the current lower bound angle (in degrees) to use for distributed angle mode in this options object. + // Note: Note: The Node will only use this if the is set to distributed angle mode. + float distributedAngleMode_lowerBound() const; + + //API Function: distributedAngleMode_lowerBound + // Sets the current lower bound angle to use for distributed angle mode in this options object. + // Note: Note: The Node will only use this if the is set to distributed angle mode. + // Note: The lower bound and upper bound angles must be at least 1 degree. + // + //Parameters: + // angle - The lower bound angle (in degrees) to use. + void distributedAngleMode_lowerBound(float angle); + + //API Function: distributedAngleMode_upperBound + // Gets the current upper bound angle (in degrees) to use for distributed angle mode in this options object. + // Note: Note: The Node will only use this if the is set to distributed angle mode. + float distributedAngleMode_upperBound() const; + + //API Function: distributedAngleMode_upperBound + // Sets the current upper bound angle to use for distributed angle mode in this options object. + // Note: Note: The Node will only use this if the is set to distributed angle mode. + // Note: The lower bound and upper bound angles must be at least 1 degree. + // + //Parameters: + // angle - The upper bound angle (in degrees) to use. + void distributedAngleMode_upperBound(float angle); + + //API Function: histogramEnable + // Gets whether sending Histograms is enabled or disabled, in this options object. + bool histogramEnable() const; + + //API Function: histogramEnable + // Sets whether sending Histograms is enabled or disabled, in this options object. + // + //Parameters: + // enable - Whehter to enable or disable sending Histograms. + void histogramEnable(bool enable); }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/HardwareGain.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/HardwareGain.cpp index 4bf2b20db..1805e6a5b 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/HardwareGain.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/HardwareGain.cpp @@ -100,6 +100,7 @@ namespace mscl case WirelessModels::node_sgLink_herm_2600: case WirelessModels::node_sgLink_herm_2700: case WirelessModels::node_sgLink_herm_2800: + case WirelessModels::node_sgLink_micro: return bitsToGain_sgLinkOem(bits); case WirelessModels::node_tcLink_1ch: @@ -146,6 +147,7 @@ namespace mscl case WirelessModels::node_sgLink_herm_2600: case WirelessModels::node_sgLink_herm_2700: case WirelessModels::node_sgLink_herm_2800: + case WirelessModels::node_sgLink_micro: return gainToBits_sgLinkOem(gain); case WirelessModels::node_tcLink_1ch: @@ -191,6 +193,7 @@ namespace mscl case WirelessModels::node_sgLink_herm_2600: case WirelessModels::node_sgLink_herm_2700: case WirelessModels::node_sgLink_herm_2800: + case WirelessModels::node_sgLink_micro: maxBits = MAX_BITS_SGLINKOEM; break; diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromHelper.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromHelper.cpp index 14bc1c288..e2163444d 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromHelper.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromHelper.cpp @@ -6,6 +6,7 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #include "stdafx.h" #include "NodeEepromHelper.h" +#include "ActivitySense.h" #include "FatigueOptions.h" #include "HardwareGain.h" #include "HistogramOptions.h" @@ -213,7 +214,7 @@ namespace mscl void NodeEepromHelper::write_numSweeps(uint32 sweeps) { //divide by 100 to write to eeprom - write( NodeEepromMap::NUM_SWEEPS, Value::UINT16(static_cast(sweeps / 100)) ); + write(NodeEepromMap::NUM_SWEEPS, Value::UINT16(static_cast(sweeps / 100))); } uint32 NodeEepromHelper::read_numSweeps() const @@ -235,7 +236,7 @@ namespace mscl } //write the value to the correct eeprom location - write( unlimitedSamplingLocation, Value::UINT16(static_cast(unlimitedDuration)) ); + write(unlimitedSamplingLocation, Value::UINT16(static_cast(unlimitedDuration))); } bool NodeEepromHelper::read_unlimitedDuration(WirelessTypes::SamplingMode samplingMode) const @@ -291,7 +292,7 @@ namespace mscl void NodeEepromHelper::write_dataFormat(WirelessTypes::DataFormat dataFormat) { - write( NodeEepromMap::DATA_FORMAT, Value::UINT16(static_cast(dataFormat)) ); + write(NodeEepromMap::DATA_FORMAT, Value::UINT16(static_cast(dataFormat))); } WirelessTypes::DataFormat NodeEepromHelper::read_dataFormat() const @@ -301,7 +302,7 @@ namespace mscl void NodeEepromHelper::write_collectionMode(WirelessTypes::DataCollectionMethod collectionMode) { - write( NodeEepromMap::COLLECTION_MODE, Value::UINT16(static_cast(collectionMode)) ); + write(NodeEepromMap::COLLECTION_MODE, Value::UINT16(static_cast(collectionMode))); } WirelessTypes::DataCollectionMethod NodeEepromHelper::read_collectionMode() const @@ -331,6 +332,7 @@ namespace mscl //these nodes all store the sampling delay in microseconds case WirelessModels::node_shmLink: case WirelessModels::node_shmLink2: + case WirelessModels::node_shmLink2_cust1: case WirelessModels::node_sgLink_herm: case WirelessModels::node_sgLink_herm_2600: case WirelessModels::node_sgLink_herm_2700: @@ -372,6 +374,7 @@ namespace mscl //these nodes all read the sampling delay in microseconds case WirelessModels::node_shmLink: case WirelessModels::node_shmLink2: + case WirelessModels::node_shmLink2_cust1: case WirelessModels::node_sgLink_herm: case WirelessModels::node_sgLink_herm_2600: case WirelessModels::node_sgLink_herm_2700: @@ -545,7 +548,7 @@ namespace mscl //make the action id from the equation (msb) and unit (lsb) values uint16 actionIdVal = Utils::make_uint16(static_cast(equation), static_cast(unit)); - + //write the action id to eeprom write(eepromLocation, Value::UINT16(actionIdVal)); } @@ -576,14 +579,37 @@ namespace mscl WirelessTypes::TransmitPower NodeEepromHelper::read_transmitPower() const { - //read and return the transmit power level - return static_cast(read(NodeEepromMap::TX_POWER_LEVEL).as_uint16()); + int16 val = read(NodeEepromMap::TX_POWER_LEVEL).as_int16(); + + if(m_node->features().supportsNewTransmitPowers()) + { + return static_cast(val); + } + else + { + //legacy value, convert to current value before returning + + //read and return the transmit power level + return WirelessTypes::legacyToTransmitPower(static_cast(val)); + } } void NodeEepromHelper::write_transmitPower(WirelessTypes::TransmitPower power) { + int16 valToWrite = 0; + + if(m_node->features().supportsNewTransmitPowers()) + { + valToWrite = static_cast(power); + } + else + { + //need to write the legacy value for the device to understand it + valToWrite = static_cast(WirelessTypes::transmitPowerToLegacy(power)); + } + //write the transmit power level to the node - write(NodeEepromMap::TX_POWER_LEVEL, Value::UINT16(static_cast(power))); + write(NodeEepromMap::TX_POWER_LEVEL, Value(valueType_int16, valToWrite)); } uint16 NodeEepromHelper::read_inactivityTimeout() const @@ -607,7 +633,7 @@ namespace mscl if(eeVal != 0) { seconds = (MAX_SLEEP_INTERVAL_EEVAL / eeVal); - } + } //if the seconds value is more than 60 seconds if(seconds > 60) @@ -732,6 +758,24 @@ namespace mscl write(eeprom, Value::UINT16(offset)); } + float NodeEepromHelper::read_gaugeFactor(const ChannelMask& mask) const + { + //find the eeprom location + const EepromLocation& eeprom = m_node->features().findEeprom(WirelessTypes::chSetting_gaugeFactor, mask); + + //read the gauge factor from eeprom + return read(eeprom).as_float(); + } + + void NodeEepromHelper::write_gaugeFactor(const ChannelMask& mask, float gaugeFactor) + { + //find the eeprom location + const EepromLocation& eeprom = m_node->features().findEeprom(WirelessTypes::chSetting_gaugeFactor, mask); + + //write the gauge factor to eeprom + write(eeprom, Value::FLOAT(gaugeFactor)); + } + WirelessTypes::ThermocoupleType NodeEepromHelper::read_thermoType(const ChannelMask& mask) const { //find the eeprom location @@ -750,6 +794,42 @@ namespace mscl write(eeprom, Value::UINT16(static_cast(thermocouple))); } + void NodeEepromHelper::read_activitySense(ActivitySense& result) const + { + //Enable/Disable + result.enabled(read(NodeEepromMap::ACT_SENSE_ENABLE).as_bool()); + + //Activity Threshold + result.activityThreshold(read(NodeEepromMap::ACT_SENSE_ACTIVE_THRES).as_float()); + + //Inactivity Threshold + result.inactivityThreshold(read(NodeEepromMap::ACT_SENSE_INACTIVE_THRES).as_float()); + + //Activity Time + result.activityTime(read(NodeEepromMap::ACT_SENSE_ACTIVE_TIME).as_float()); + + //Inactivity Timeout + result.inactivityTimeout(read(NodeEepromMap::ACT_SENSE_INACTIVE_TIMEOUT).as_float()); + } + + void NodeEepromHelper::write_activitySense(const ActivitySense& options) + { + //Enable/Disable + write(NodeEepromMap::ACT_SENSE_ENABLE, Value::UINT16(static_cast(options.enabled()))); + + //Activity Threshold + write(NodeEepromMap::ACT_SENSE_ACTIVE_THRES, Value::FLOAT(options.activityThreshold())); + + //Inactivity Threshold + write(NodeEepromMap::ACT_SENSE_INACTIVE_THRES, Value::FLOAT(options.inactivityThreshold())); + + //Activity Time + write(NodeEepromMap::ACT_SENSE_ACTIVE_TIME, Value::FLOAT(options.activityTime())); + + //Inactivity Timeout + write(NodeEepromMap::ACT_SENSE_INACTIVE_TIMEOUT, Value::FLOAT(options.inactivityTimeout())); + } + void NodeEepromHelper::read_fatigueOptions(FatigueOptions& result) const { const NodeFeatures& features = m_node->features(); @@ -776,10 +856,10 @@ namespace mscl result.peakValleyThreshold(read(NodeEepromMap::PEAK_VALLEY_THRES).as_uint16()); //Raw Mode - if(features.supportsFatigueRawModeConfig()) + if(features.supportsFatigueDebugModeConfig()) { - bool rawModeEnabled = (read(NodeEepromMap::HISTOGRAM_RAW_FLAG).as_uint16() == 1); - result.rawMode(rawModeEnabled); + bool debugModeEnabled = (read(NodeEepromMap::HISTOGRAM_RAW_FLAG).as_uint16() == 1); + result.debugMode(debugModeEnabled); } //============================= @@ -837,6 +917,31 @@ namespace mscl result.snCurveSegment(2, SnCurveSegment(read(NodeEepromMap::SNCURVE_M_3).as_float(), read(NodeEepromMap::SNCURVE_LOGA_3).as_float())); } //============================= + + //============================= + //Fatigue Mode / Distributed Angle Settings + if(features.supportsFatigueModeConfig()) + { + result.fatigueMode(static_cast(read(NodeEepromMap::FATIGUE_MODE).as_uint16())); + } + + //============================= + //Distributed Angle Settings + if(features.supportsFatigueMode(WirelessTypes::fatigueMode_distributedAngle)) + { + result.distributedAngleMode_numAngles(read(NodeEepromMap::DIST_ANGLE_NUM_ANGLES).as_uint8()); + + result.distributedAngleMode_lowerBound(read(NodeEepromMap::DIST_ANGLE_LOWER_BOUND).as_float()); + + result.distributedAngleMode_upperBound(read(NodeEepromMap::DIST_ANGLE_UPPER_BOUND).as_float()); + } + //============================= + + //Histogram Toggle + if(features.supportsHistogramEnableConfig()) + { + result.histogramEnable(read(NodeEepromMap::HISTOGRAM_ENABLE).as_bool()); + } } void NodeEepromHelper::write_fatigueOptions(const FatigueOptions& options) @@ -865,9 +970,9 @@ namespace mscl write(NodeEepromMap::PEAK_VALLEY_THRES, Value::UINT16(options.peakValleyThreshold())); //Raw Mode - if(features.supportsFatigueRawModeConfig()) + if(features.supportsFatigueDebugModeConfig()) { - write(NodeEepromMap::HISTOGRAM_RAW_FLAG, Value::UINT16(static_cast(options.rawMode()))); + write(NodeEepromMap::HISTOGRAM_RAW_FLAG, Value::UINT16(static_cast(options.debugMode()))); } //============================= @@ -942,6 +1047,31 @@ namespace mscl write(NodeEepromMap::SNCURVE_LOGA_3, Value::FLOAT(segment->second.logA())); } //============================= + + //============================= + //Fatigue Mode + if(features.supportsFatigueModeConfig()) + { + write(NodeEepromMap::FATIGUE_MODE, Value::UINT16(static_cast(options.fatigueMode()))); + } + + //============================= + //Distributed Angle Settings + if(features.supportsFatigueMode(WirelessTypes::fatigueMode_distributedAngle)) + { + write(NodeEepromMap::DIST_ANGLE_NUM_ANGLES, Value::UINT16(static_cast(options.distributedAngleMode_numAngles()))); + + write(NodeEepromMap::DIST_ANGLE_LOWER_BOUND, Value::FLOAT(options.distributedAngleMode_lowerBound())); + + write(NodeEepromMap::DIST_ANGLE_UPPER_BOUND, Value::FLOAT(options.distributedAngleMode_upperBound())); + } + //============================= + + //Histogram Toggle + if(features.supportsHistogramEnableConfig()) + { + write(NodeEepromMap::HISTOGRAM_ENABLE, Value::UINT16(static_cast(options.histogramEnable()))); + } } void NodeEepromHelper::read_histogramOptions(HistogramOptions& result) const diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromHelper.h b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromHelper.h index 5a32b68d9..ef725df09 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromHelper.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromHelper.h @@ -19,9 +19,10 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. namespace mscl { //forward declarations - class WirelessNode_Impl; + class ActivitySense; class FatigueOptions; class HistogramOptions; + class WirelessNode_Impl; //Class: NodeEepromHelper // A helper class for reading and writing to a Wireless Node's Eeprom. @@ -837,6 +838,34 @@ namespace mscl // - : A connection error has occurred with the parent BaseStation. void write_hardwareOffset(const ChannelMask& mask, uint16 offset); + //Function: read_gaugeFactor + // Reads the gauge factor for the specified from the Node. + // + //Parameters: + // mask - The to read the gauge factor for. + // + //Returns: + // The gauge factor for the given . + // + //Exceptions: + // - : Gauge Factor is not supported for the given or Node. + // - : Failed to communicate with the Node. + // - : A connection error has occurred with the parent BaseStation. + float read_gaugeFactor(const ChannelMask& mask) const; + + //Function: write_gaugeFactor + // Writes the gauge factor value for the specified to the Node. + // + //Parameters: + // mask - The to write the gauge factor for. + // gaugeFactor - The gauge factor value to write to the Node. + // + //Exceptions: + // - : Gauge Factor is not supported for the given or Node. + // - : Failed to communicate with the Node. + // - : A connection error has occurred with the parent BaseStation. + void write_gaugeFactor(const ChannelMask& mask, float gaugeFactor); + //Function: read_thermoType // Reads the from the Node. // @@ -866,6 +895,32 @@ namespace mscl // - : A connection error has occurred with the parent BaseStation. void write_thermoType(const ChannelMask& mask, WirelessTypes::ThermocoupleType thermocouple); + //Function: read_activitySense + // Reads the options from the Node. + // This assumes activity sense configuration is supported by the Node. + // + //Parameters: + // result - Will hold the result of the options read from the Node. + // + //Exceptions: + // - : Unsupported eeprom location. + // - : Failed to communicate with the Node. + // - : A connection error has occurred with the parent BaseStation. + void read_activitySense(ActivitySense& result) const; + + //Function: write_activitySense + // Writes the options to the Node. + // This assumes fatigue options configuration is supported by the Node. + // + //Parameters: + // options - The to write to the Node. + // + //Exceptions: + // - : Unsupported eeprom location. + // - : Failed to communicate with the Node. + // - : A connection error has occurred with the parent BaseStation. + void write_activitySense(const ActivitySense& options); + //Function: read_fatigueOptions // Reads the from the Node. // This assumes fatigue options configuration is supported by the Node. @@ -931,6 +986,7 @@ namespace mscl //Function: read_lostBeaconTimeout // Reads the lost beacon timeout value from the Node. // A value of 0 means the timeout is disabled. + // This assumes lost beacon timeout is supported by the Node. // //Returns: // The lost beacon timeout in minutes. diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromMap.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromMap.cpp index b45ce7ce1..8228ffdf6 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromMap.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromMap.cpp @@ -10,153 +10,168 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. namespace mscl { - const EepromLocation NodeEepromMap::CURRENT_LOG_PAGE (0, valueType_uint16); - const EepromLocation NodeEepromMap::CURRENT_PAGE_OFFSET (2, valueType_uint16); - const EepromLocation NodeEepromMap::DATA_SETS_STORED (4, valueType_uint16); - const EepromLocation NodeEepromMap::ACTIVE_CHANNEL_MASK (12, valueType_uint16); - const EepromLocation NodeEepromMap::DATALOG_SAMPLE_RATE (14, valueType_uint16); - const EepromLocation NodeEepromMap::NUM_SWEEPS (16, valueType_uint16); - const EepromLocation NodeEepromMap::DEFAULT_MODE (18, valueType_uint16); - const EepromLocation NodeEepromMap::SERIAL_ID (20, valueType_uint32); - const EepromLocation NodeEepromMap::SAMPLING_MODE (24, valueType_uint16); - const EepromLocation NodeEepromMap::HW_OFFSET_1 (26, valueType_uint16); - const EepromLocation NodeEepromMap::HW_OFFSET_2 (28, valueType_uint16); - const EepromLocation NodeEepromMap::HW_OFFSET_3 (30, valueType_uint16); - const EepromLocation NodeEepromMap::HW_OFFSET_4 (32, valueType_uint16); - const EepromLocation NodeEepromMap::SAMPLING_DELAY (34, valueType_uint16); - const EepromLocation NodeEepromMap::TDMA_ADDRESS (36, valueType_uint16); - const EepromLocation NodeEepromMap::COLLECTION_MODE (38, valueType_uint16); - const EepromLocation NodeEepromMap::NUM_BUFF_PACKETS (40, valueType_uint16); - const EepromLocation NodeEepromMap::NUM_RETRAN_ATTEMPTS (44, valueType_uint16); - const EepromLocation NodeEepromMap::MODEL_NUMBER (46, valueType_uint16); - const EepromLocation NodeEepromMap::MODEL_OPTION (48, valueType_uint16); - const EepromLocation NodeEepromMap::NODE_ADDRESS (50, valueType_uint16); - const EepromLocation NodeEepromMap::SLEEP_INTERVAL (66, valueType_uint16); - const EepromLocation NodeEepromMap::INACTIVE_TIMEOUT (70, valueType_uint16); - const EepromLocation NodeEepromMap::SAMPLE_RATE (72, valueType_uint16); - const EepromLocation NodeEepromMap::DATA_FORMAT (76, valueType_uint16); - const EepromLocation NodeEepromMap::SNIFF_DURATION (78, valueType_uint16); - const EepromLocation NodeEepromMap::FREQUENCY (90, valueType_uint16); - const EepromLocation NodeEepromMap::TX_POWER_LEVEL (94, valueType_uint16); - const EepromLocation NodeEepromMap::UNLIMITED_SAMPLING (100, valueType_uint16); - const EepromLocation NodeEepromMap::UNLIMITED_DATALOG (102, valueType_uint16); - const EepromLocation NodeEepromMap::FIRMWARE_VER (108, valueType_uint16); - const EepromLocation NodeEepromMap::FIRMWARE_VER2 (110, valueType_uint16); - const EepromLocation NodeEepromMap::LEGACY_MODEL_NUMBER (112, valueType_uint16); - const EepromLocation NodeEepromMap::LEGACY_SERIAL_ID (114, valueType_uint16); - const EepromLocation NodeEepromMap::MAX_MEMORY (116, valueType_uint16); - const EepromLocation NodeEepromMap::MICROCONTROLLER (120, valueType_uint16); - const EepromLocation NodeEepromMap::FW_ARCH_VER (122, valueType_uint16); - const EepromLocation NodeEepromMap::HW_GAIN_1 (128, valueType_uint16); - const EepromLocation NodeEepromMap::HW_GAIN_2 (130, valueType_uint16); - const EepromLocation NodeEepromMap::HW_GAIN_3 (132, valueType_uint16); - const EepromLocation NodeEepromMap::HW_GAIN_4 (134, valueType_uint16); - const EepromLocation NodeEepromMap::CH_ACTION_ID_1 (150, valueType_uint16); - const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_1 (152, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_1 (156, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_ID_2 (160, valueType_uint16); - const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_2 (162, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_2 (166, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_ID_3 (170, valueType_uint16); - const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_3 (172, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_3 (176, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_ID_4 (180, valueType_uint16); - const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_4 (182, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_4 (186, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_ID_5 (190, valueType_uint16); - const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_5 (192, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_5 (196, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_ID_6 (200, valueType_uint16); - const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_6 (202, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_6 (206, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_ID_7 (210, valueType_uint16); - const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_7 (212, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_7 (216, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_ID_8 (220, valueType_uint16); - const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_8 (222, valueType_float); - const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_8 (226, valueType_float); - const EepromLocation NodeEepromMap::BOOTLOADER_VER (236, valueType_uint16); - const EepromLocation NodeEepromMap::RESET_COUNTER (246, valueType_uint16); - const EepromLocation NodeEepromMap::CYCLE_POWER (250, valueType_uint16); - const EepromLocation NodeEepromMap::RADIO_OPTIONS (258, valueType_uint16); - const EepromLocation NodeEepromMap::LOST_BEACON_TIMEOUT (260, valueType_uint16); - const EepromLocation NodeEepromMap::SYNC_SAMPLE_SETTING (262, valueType_uint16); - const EepromLocation NodeEepromMap::TX_PER_GROUP (264, valueType_uint16); - const EepromLocation NodeEepromMap::GROUP_SIZE (266, valueType_uint16); - const EepromLocation NodeEepromMap::TIME_BETW_SESSIONS (268, valueType_uint16); - const EepromLocation NodeEepromMap::NODE_RETRANSMIT (272, valueType_uint16); - const EepromLocation NodeEepromMap::MAX_RETRANS_PACKET (274, valueType_uint16); - const EepromLocation NodeEepromMap::MAX_RETRANS_BURST (276, valueType_uint16); - const EepromLocation NodeEepromMap::REGION_CODE (280, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_SAMPLE_RATE (328, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_CHANNEL_MASK (330, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_PRE_DURATION (332, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_POST_DURATION (334, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_SRC_1 (336, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_OPER_1 (338, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL1_1 (340, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL2_1 (342, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_SRC_2 (344, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_OPER_2 (346, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL1_2 (348, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL2_2 (350, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_SRC_3 (352, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_OPER_3 (354, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL1_3 (356, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL2_3 (358, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_SRC_4 (360, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_OPER_4 (362, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL1_4 (364, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL2_4 (366, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_SRC_5 (368, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_OPER_5 (370, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL1_5 (372, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL2_5 (374, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_SRC_6 (376, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_OPER_6 (378, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL1_6 (380, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL2_6 (382, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_SRC_7 (384, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_OPER_7 (386, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL1_7 (388, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL2_7 (390, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_SRC_8 (392, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_OPER_8 (394, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL1_8 (396, valueType_uint16); - const EepromLocation NodeEepromMap::EVENT_VAL2_8 (398, valueType_uint16); - const EepromLocation NodeEepromMap::CHANNEL_FILTER (440, valueType_uint16); - const EepromLocation NodeEepromMap::MIN_SOFT_VER_MAJOR (480, valueType_uint16); - const EepromLocation NodeEepromMap::MIN_SOFT_VER_MINOR (482, valueType_uint16); - const EepromLocation NodeEepromMap::HW_OFFSET_5 (504, valueType_uint16); - const EepromLocation NodeEepromMap::HW_OFFSET_6 (506, valueType_uint16); - const EepromLocation NodeEepromMap::HW_OFFSET_7 (508, valueType_uint16); - const EepromLocation NodeEepromMap::HW_OFFSET_8 (510, valueType_uint16); - - const EepromLocation NodeEepromMap::THERMOCPL_TYPE (306, valueType_uint16); - const EepromLocation NodeEepromMap::FILTER_1 (130, valueType_uint16); - const EepromLocation NodeEepromMap::FILTER_2 (134, valueType_uint16); - - - const EepromLocation NodeEepromMap::DAMAGE_ANGLE_1 (512, valueType_float); - const EepromLocation NodeEepromMap::DAMAGE_ANGLE_2 (516, valueType_float); - const EepromLocation NodeEepromMap::DAMAGE_ANGLE_3 (520, valueType_float); - const EepromLocation NodeEepromMap::LEGACY_DAMAGE_ANGLE_1 (676, valueType_uint16); - const EepromLocation NodeEepromMap::LEGACY_DAMAGE_ANGLE_2 (678, valueType_uint16); - const EepromLocation NodeEepromMap::LEGACY_DAMAGE_ANGLE_3 (680, valueType_uint16); - const EepromLocation NodeEepromMap::BIN_SIZE (682, valueType_uint16); - const EepromLocation NodeEepromMap::RESET_BINS (684, valueType_uint16); - const EepromLocation NodeEepromMap::BIN_START (686, valueType_uint16); - const EepromLocation NodeEepromMap::PEAK_VALLEY_THRES (688, valueType_uint16); - const EepromLocation NodeEepromMap::SNCURVE_LOGA_1 (700, valueType_float); - const EepromLocation NodeEepromMap::SNCURVE_M_1 (704, valueType_float); - const EepromLocation NodeEepromMap::SNCURVE_LOGA_2 (708, valueType_float); - const EepromLocation NodeEepromMap::SNCURVE_M_2 (712, valueType_float); - const EepromLocation NodeEepromMap::SNCURVE_LOGA_3 (716, valueType_float); - const EepromLocation NodeEepromMap::SNCURVE_M_3 (720, valueType_float); - const EepromLocation NodeEepromMap::YOUNGS_MODULUS (724, valueType_float); - const EepromLocation NodeEepromMap::POISSONS_RATIO (728, valueType_float); - const EepromLocation NodeEepromMap::HISTOGRAM_SAMPLE_RATE (732, valueType_uint16); - const EepromLocation NodeEepromMap::HISTOGRAM_RAW_FLAG (734, valueType_uint16); + const EepromLocation NodeEepromMap::CURRENT_LOG_PAGE (0, valueType_uint16); + const EepromLocation NodeEepromMap::CURRENT_PAGE_OFFSET (2, valueType_uint16); + const EepromLocation NodeEepromMap::DATA_SETS_STORED (4, valueType_uint16); + const EepromLocation NodeEepromMap::ACTIVE_CHANNEL_MASK (12, valueType_uint16); + const EepromLocation NodeEepromMap::DATALOG_SAMPLE_RATE (14, valueType_uint16); + const EepromLocation NodeEepromMap::NUM_SWEEPS (16, valueType_uint16); + const EepromLocation NodeEepromMap::DEFAULT_MODE (18, valueType_uint16); + const EepromLocation NodeEepromMap::SERIAL_ID (20, valueType_uint32); + const EepromLocation NodeEepromMap::SAMPLING_MODE (24, valueType_uint16); + const EepromLocation NodeEepromMap::HW_OFFSET_1 (26, valueType_uint16); + const EepromLocation NodeEepromMap::HW_OFFSET_2 (28, valueType_uint16); + const EepromLocation NodeEepromMap::HW_OFFSET_3 (30, valueType_uint16); + const EepromLocation NodeEepromMap::HW_OFFSET_4 (32, valueType_uint16); + const EepromLocation NodeEepromMap::SAMPLING_DELAY (34, valueType_uint16); + const EepromLocation NodeEepromMap::TDMA_ADDRESS (36, valueType_uint16); + const EepromLocation NodeEepromMap::COLLECTION_MODE (38, valueType_uint16); + const EepromLocation NodeEepromMap::NUM_BUFF_PACKETS (40, valueType_uint16); + const EepromLocation NodeEepromMap::NUM_RETRAN_ATTEMPTS (44, valueType_uint16); + const EepromLocation NodeEepromMap::MODEL_NUMBER (46, valueType_uint16); + const EepromLocation NodeEepromMap::MODEL_OPTION (48, valueType_uint16); + const EepromLocation NodeEepromMap::NODE_ADDRESS (50, valueType_uint16); + const EepromLocation NodeEepromMap::SLEEP_INTERVAL (66, valueType_uint16); + const EepromLocation NodeEepromMap::INACTIVE_TIMEOUT (70, valueType_uint16); + const EepromLocation NodeEepromMap::SAMPLE_RATE (72, valueType_uint16); + const EepromLocation NodeEepromMap::DATA_FORMAT (76, valueType_uint16); + const EepromLocation NodeEepromMap::SNIFF_DURATION (78, valueType_uint16); + const EepromLocation NodeEepromMap::FREQUENCY (90, valueType_uint16); + const EepromLocation NodeEepromMap::TX_POWER_LEVEL (94, valueType_int16); + const EepromLocation NodeEepromMap::UNLIMITED_SAMPLING (100, valueType_uint16); + const EepromLocation NodeEepromMap::UNLIMITED_DATALOG (102, valueType_uint16); + const EepromLocation NodeEepromMap::FIRMWARE_VER (108, valueType_uint16); + const EepromLocation NodeEepromMap::FIRMWARE_VER2 (110, valueType_uint16); + const EepromLocation NodeEepromMap::LEGACY_MODEL_NUMBER (112, valueType_uint16); + const EepromLocation NodeEepromMap::LEGACY_SERIAL_ID (114, valueType_uint16); + const EepromLocation NodeEepromMap::MAX_MEMORY (116, valueType_uint16); + const EepromLocation NodeEepromMap::MICROCONTROLLER (120, valueType_uint16); + const EepromLocation NodeEepromMap::FW_ARCH_VER (122, valueType_uint16); + const EepromLocation NodeEepromMap::HW_GAIN_1 (128, valueType_uint16); + const EepromLocation NodeEepromMap::HW_GAIN_2 (130, valueType_uint16); + const EepromLocation NodeEepromMap::HW_GAIN_3 (132, valueType_uint16); + const EepromLocation NodeEepromMap::HW_GAIN_4 (134, valueType_uint16); + const EepromLocation NodeEepromMap::CH_ACTION_ID_1 (150, valueType_uint16); + const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_1 (152, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_1 (156, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_ID_2 (160, valueType_uint16); + const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_2 (162, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_2 (166, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_ID_3 (170, valueType_uint16); + const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_3 (172, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_3 (176, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_ID_4 (180, valueType_uint16); + const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_4 (182, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_4 (186, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_ID_5 (190, valueType_uint16); + const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_5 (192, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_5 (196, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_ID_6 (200, valueType_uint16); + const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_6 (202, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_6 (206, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_ID_7 (210, valueType_uint16); + const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_7 (212, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_7 (216, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_ID_8 (220, valueType_uint16); + const EepromLocation NodeEepromMap::CH_ACTION_SLOPE_8 (222, valueType_float); + const EepromLocation NodeEepromMap::CH_ACTION_OFFSET_8 (226, valueType_float); + const EepromLocation NodeEepromMap::BOOTLOADER_VER (236, valueType_uint16); + const EepromLocation NodeEepromMap::RESET_COUNTER (246, valueType_uint16); + const EepromLocation NodeEepromMap::CYCLE_POWER (250, valueType_uint16); + const EepromLocation NodeEepromMap::RADIO_OPTIONS (258, valueType_uint16); + const EepromLocation NodeEepromMap::LOST_BEACON_TIMEOUT (260, valueType_uint16); + const EepromLocation NodeEepromMap::SYNC_SAMPLE_SETTING (262, valueType_uint16); + const EepromLocation NodeEepromMap::TX_PER_GROUP (264, valueType_uint16); + const EepromLocation NodeEepromMap::GROUP_SIZE (266, valueType_uint16); + const EepromLocation NodeEepromMap::TIME_BETW_SESSIONS (268, valueType_uint16); + const EepromLocation NodeEepromMap::NODE_RETRANSMIT (272, valueType_uint16); + const EepromLocation NodeEepromMap::MAX_RETRANS_PACKET (274, valueType_uint16); + const EepromLocation NodeEepromMap::MAX_RETRANS_BURST (276, valueType_uint16); + const EepromLocation NodeEepromMap::REGION_CODE (280, valueType_uint16); + const EepromLocation NodeEepromMap::DATA_PACKET_FORMAT (292, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_SAMPLE_RATE (328, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_CHANNEL_MASK (330, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_PRE_DURATION (332, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_POST_DURATION (334, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_SRC_1 (336, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_OPER_1 (338, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL1_1 (340, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL2_1 (342, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_SRC_2 (344, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_OPER_2 (346, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL1_2 (348, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL2_2 (350, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_SRC_3 (352, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_OPER_3 (354, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL1_3 (356, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL2_3 (358, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_SRC_4 (360, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_OPER_4 (362, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL1_4 (364, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL2_4 (366, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_SRC_5 (368, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_OPER_5 (370, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL1_5 (372, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL2_5 (374, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_SRC_6 (376, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_OPER_6 (378, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL1_6 (380, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL2_6 (382, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_SRC_7 (384, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_OPER_7 (386, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL1_7 (388, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL2_7 (390, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_SRC_8 (392, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_OPER_8 (394, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL1_8 (396, valueType_uint16); + const EepromLocation NodeEepromMap::EVENT_VAL2_8 (398, valueType_uint16); + const EepromLocation NodeEepromMap::CHANNEL_FILTER (440, valueType_uint16); + const EepromLocation NodeEepromMap::MIN_SOFT_VER_MAJOR (480, valueType_uint16); + const EepromLocation NodeEepromMap::MIN_SOFT_VER_MINOR (482, valueType_uint16); + const EepromLocation NodeEepromMap::HW_OFFSET_5 (504, valueType_uint16); + const EepromLocation NodeEepromMap::HW_OFFSET_6 (506, valueType_uint16); + const EepromLocation NodeEepromMap::HW_OFFSET_7 (508, valueType_uint16); + const EepromLocation NodeEepromMap::HW_OFFSET_8 (510, valueType_uint16); + const EepromLocation NodeEepromMap::GAUGE_FACTOR_1 (782, valueType_float); + const EepromLocation NodeEepromMap::GAUGE_FACTOR_2 (786, valueType_float); + const EepromLocation NodeEepromMap::GAUGE_FACTOR_3 (790, valueType_float); + const EepromLocation NodeEepromMap::GAUGE_FACTOR_4 (794, valueType_float); + + const EepromLocation NodeEepromMap::THERMOCPL_TYPE (306, valueType_uint16); + const EepromLocation NodeEepromMap::FILTER_1 (130, valueType_uint16); + const EepromLocation NodeEepromMap::FILTER_2 (134, valueType_uint16); + + const EepromLocation NodeEepromMap::LEGACY_DAMAGE_ANGLE_1 (676, valueType_uint16); + const EepromLocation NodeEepromMap::LEGACY_DAMAGE_ANGLE_2 (678, valueType_uint16); + const EepromLocation NodeEepromMap::LEGACY_DAMAGE_ANGLE_3 (680, valueType_uint16); + const EepromLocation NodeEepromMap::BIN_SIZE (682, valueType_uint16); + const EepromLocation NodeEepromMap::RESET_BINS (684, valueType_uint16); + const EepromLocation NodeEepromMap::BIN_START (686, valueType_uint16); + const EepromLocation NodeEepromMap::PEAK_VALLEY_THRES (688, valueType_uint16); + const EepromLocation NodeEepromMap::SNCURVE_LOGA_1 (700, valueType_float); + const EepromLocation NodeEepromMap::SNCURVE_M_1 (704, valueType_float); + const EepromLocation NodeEepromMap::SNCURVE_LOGA_2 (708, valueType_float); + const EepromLocation NodeEepromMap::SNCURVE_M_2 (712, valueType_float); + const EepromLocation NodeEepromMap::SNCURVE_LOGA_3 (716, valueType_float); + const EepromLocation NodeEepromMap::SNCURVE_M_3 (720, valueType_float); + const EepromLocation NodeEepromMap::YOUNGS_MODULUS (724, valueType_float); + const EepromLocation NodeEepromMap::POISSONS_RATIO (728, valueType_float); + const EepromLocation NodeEepromMap::HISTOGRAM_SAMPLE_RATE (732, valueType_uint16); + const EepromLocation NodeEepromMap::DAMAGE_ANGLE_1 (734, valueType_float); + const EepromLocation NodeEepromMap::DAMAGE_ANGLE_2 (738, valueType_float); + const EepromLocation NodeEepromMap::DAMAGE_ANGLE_3 (742, valueType_float); + const EepromLocation NodeEepromMap::FATIGUE_MODE (746, valueType_uint16); + const EepromLocation NodeEepromMap::DIST_ANGLE_NUM_ANGLES (748, valueType_uint16); + const EepromLocation NodeEepromMap::DIST_ANGLE_LOWER_BOUND (750, valueType_float); + const EepromLocation NodeEepromMap::DIST_ANGLE_UPPER_BOUND (754, valueType_float); + const EepromLocation NodeEepromMap::HISTOGRAM_RAW_FLAG (826, valueType_uint16); + const EepromLocation NodeEepromMap::ACT_SENSE_ENABLE (834, valueType_uint16); + const EepromLocation NodeEepromMap::ACT_SENSE_ACTIVE_THRES (836, valueType_float); + const EepromLocation NodeEepromMap::ACT_SENSE_INACTIVE_TIMEOUT (840, valueType_float); + const EepromLocation NodeEepromMap::ACT_SENSE_ACTIVE_TIME (844, valueType_float); + const EepromLocation NodeEepromMap::ACT_SENSE_INACTIVE_THRES (848, valueType_float); + const EepromLocation NodeEepromMap::HISTOGRAM_ENABLE (852, valueType_uint16); + bool NodeEepromMap::canUseCache_read(uint16 eepromLocation) { diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromMap.h b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromMap.h index cd8bdc554..0fcc4fe7f 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromMap.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/NodeEepromMap.h @@ -53,281 +53,334 @@ namespace mscl //======================================================================================================================= //Constants: Eeprom Locations // - // CURRENT_LOG_PAGE -The next flash page to be used for datalogging - // CURRENT_PAGE_OFFSET -The byte offset location for the next datalogging session - // DATA_SETS_STORED -The # of datalogging sessions (triggers) stored in flash memory - // ACTIVE_CHANNEL_MASK -The channels that are enabled/disabled and will be sampled - // DATALOG_SAMPLE_RATE -The sample rate for Armed Datalogging sampling - // NUM_SWEEPS -The # of sweeps (samples per data set) to sample for - // DEFAULT_MODE -The default mode to allow the node to perform different operations on startup and after timeout - // SERIAL_ID -The serial ID for the node. Combine with the model number for the full serial number - // SAMPLING_MODE -The sampling mode of the node (Sync Sampling, Non-Sync Sampling, Armed Datalogging, etc.) - // HW_OFFSET_1 -The hardware offset of channel 1 - // HW_OFFSET_2 -The hardware offset of channel 2 - // HW_OFFSET_3 -The hardware offset of channel 3 - // HW_OFFSET_4 -The hardware offset of channel 4 - // HW_OFFSET_5 -The hardware offset of channel 5 - // HW_OFFSET_6 -The hardware offset of channel 6 - // HW_OFFSET_7 -The hardware offset of channel 7 - // HW_OFFSET_8 -The hardware offset of channel 8 - // SAMPLING_DELAY -The sampling delay (amount of time between sensor excitation power up and A/D sampling - // TDMA_ADDRESS -The TDMA network address used for Synchronized Sampling - // COLLECTION_MODE -The data collection mode (log, transmit) that affects standard sampling modes - // NUM_BUFF_PACKETS -The # of buffered packets - // NUM_RETRAN_ATTEMPTS -The # of retransmit attempts - // NODE_ADDRESS -The node address of the wireless node - // SLEEP_INTERVAL -The listen-for-wakeup interval for the node - // INACTIVE_TIMEOUT -The length of time necessary before a node enters sleep mode, if no user activity - // SAMPLE_RATE -The sample rate for standard sampling modes (Synchronized Sampling, LDC) - // DATA_FORMAT -The packet format (uint16, float, etc.) of sampled data - // SNIFF_DURATION -The amount of time that the node listens for a wake packets - // FREQUENCY -The radio frequency channel - // TX_POWER_LEVEL -The transmit output power of the radio - // UNLIMITED_SAMPLING -The unlimited sampling flag for standard sampling modes - // UNLIMITED_DATALOG -The unlimited sampling flag for Armed Datalogging sampling - // FIRMWARE_VER -The firmware version of the node (part 1) - // FIRMWARE_VER2 -The firmware version of the node (part 2) - // MODEL_NUMBER -The model number of the node - // MODEL_OPTION -The model option of the node - // LEGACY_MODEL_NUMBER -The (legacy) model number of the node - // LEGACY_SERIAL_ID -The (legacy) serial ID for the node. Combine with the model number for the full serial number - // MAX_MEMORY -The maximum number of pages available on the flash memory - // MICROCONTROLLER -The ID of the microcontroller - // FW_ARCH_VER -The firmware architecture version - // HW_GAIN_1 -The hardware gain of channel 1 - // HW_GAIN_2 -The hardware gain of channel 2 - // HW_GAIN_3 -The hardware gain of channel 3 - // HW_GAIN_4 -The hardware gain of channel 4 - // HW_GAIN_5 -The hardware gain of channel 5 - // HW_GAIN_6 -The hardware gain of channel 6 - // HW_GAIN_7 -The hardware gain of channel 7 - // HW_GAIN_8 -The hardware gain of channel 8 - // CH_ACTION_ID_1 -The channel action ID of channel 1 - // CH_ACTION_SLOPE_1 -The channel action slope of channel 1 - // CH_ACTION_OFFSET_1 -The channel action offset of channel 1 - // CH_ACTION_ID_2 -The channel action ID of channel 2 - // CH_ACTION_SLOPE_2 -The channel action slope of channel 2 - // CH_ACTION_OFFSET_2 -The channel action offset of channel 2 - // CH_ACTION_ID_3 -The channel action ID of channel 3 - // CH_ACTION_SLOPE_3 -The channel action slope of channel 3 - // CH_ACTION_OFFSET_3 -The channel action offset of channel 3 - // CH_ACTION_ID_4 -The channel action ID of channel 4 - // CH_ACTION_SLOPE_4 -The channel action slope of channel 4 - // CH_ACTION_OFFSET_4 -The channel action offset of channel 4 - // CH_ACTION_ID_5 -The channel action ID of channel 5 - // CH_ACTION_SLOPE_5 -The channel action slope of channel 5 - // CH_ACTION_OFFSET_5 -The channel action offset of channel 5 - // CH_ACTION_ID_6 -The channel action ID of channel 6 - // CH_ACTION_SLOPE_6 -The channel action slope of channel 6 - // CH_ACTION_OFFSET_6 -The channel action offset of channel 6 - // CH_ACTION_ID_7 -The channel action ID of channel 7 - // CH_ACTION_SLOPE_7 -The channel action slope of channel 7 - // CH_ACTION_OFFSET_7 -The channel action offset of channel 7 - // CH_ACTION_ID_8 -The channel action ID of channel 8 - // CH_ACTION_SLOPE_8 -The channel action slope of channel 8 - // CH_ACTION_OFFSET_8 -The channel action offset of channel 8 - // BOOTLOADER_VER -The bootloader version number - // RESET_COUNTER -The number of times the node has been turned on - // CYCLE_POWER -Used to soft reset the node or the radio on the node - // RADIO_OPTIONS -The options of the current radio (XR enabled or not, etc.) - // LOST_BEACON_TIMEOUT -The time for a node to wait before entering a low power state when no longer hearing a beacon in Sync Sampling - // SYNC_SAMPLE_SETTING -The Synchronized Sampling mode (Burst, Continuous, etc.) - // TX_PER_GROUP -The transmissions per group for Synchronized Sampling - // GROUP_SIZE -The group size for Synchronized Sampling - // TIME_BETW_SESSIONS -The time between each burst for Synchronized Sampling - // NODE_RETRANSMIT -Node retranmission enable/disable (for Lossless) - // MAX_RETRANS_PACKET -The max retransmits per packet - // MAX_RETRANS_BURST -The max retransmits per burst - // REGION_CODE -The region code for the device - // EVENT_SAMPLE_RATE -Event Driven Sampling: Sample Rate - // EVENT_CHANNEL_MASK -Event Driven Sampling: Channel Mask - // EVENT_PRE_DURATION -Event Driven Sampling: Pre-Event Duration - // EVENT_POST_DURATION -Event Driven Sampling: Post-Event Duration - // EVENT_SRC_1 -Event Driven Sampling: The source for Event 1 - // EVENT_OPER_1 -Event Driven Sampling: The operation for Event 1 - // EVENT_VAL1_1 -Event Driven Sampling: Value 1 for Event 1 - // EVENT_VAL2_1 -Event Driven Sampling: Value 2 for Event 1 - // EVENT_SRC_2 -Event Driven Sampling: The source for Event 2 - // EVENT_OPER_2 -Event Driven Sampling: The operation for Event 2 - // EVENT_VAL1_2 -Event Driven Sampling: Value 1 for Event 2 - // EVENT_VAL2_2 -Event Driven Sampling: Value 2 for Event 2 - // EVENT_SRC_3 -Event Driven Sampling: The source for Event 3 - // EVENT_OPER_3 -Event Driven Sampling: The operation for Event 3 - // EVENT_VAL1_3 -Event Driven Sampling: Value 1 for Event 3 - // EVENT_VAL2_3 -Event Driven Sampling: Value 2 for Event 3 - // EVENT_SRC_4 -Event Driven Sampling: The source for Event 4 - // EVENT_OPER_4 -Event Driven Sampling: The operation for Event 4 - // EVENT_VAL1_4 -Event Driven Sampling: Value 1 for Event 4 - // EVENT_VAL2_4 -Event Driven Sampling: Value 2 for Event 4 - // EVENT_SRC_5 -Event Driven Sampling: The source for Event 5 - // EVENT_OPER_5 -Event Driven Sampling: The operation for Event 5 - // EVENT_VAL1_5 -Event Driven Sampling: Value 1 for Event 5 - // EVENT_VAL2_5 -Event Driven Sampling: Value 2 for Event 5 - // EVENT_SRC_6 -Event Driven Sampling: The source for Event 6 - // EVENT_OPER_6 -Event Driven Sampling: The operation for Event 6 - // EVENT_VAL1_6 -Event Driven Sampling: Value 1 for Event 6 - // EVENT_VAL2_6 -Event Driven Sampling: Value 2 for Event 6 - // EVENT_SRC_7 -Event Driven Sampling: The source for Event 7 - // EVENT_OPER_7 -Event Driven Sampling: The operation for Event 7 - // EVENT_VAL1_7 -Event Driven Sampling: Value 1 for Event 7 - // EVENT_VAL2_7 -Event Driven Sampling: Value 2 for Event 7 - // EVENT_SRC_8 -Event Driven Sampling: The source for Event 8 - // EVENT_OPER_8 -Event Driven Sampling: The operation for Event 8 - // EVENT_VAL1_8 -Event Driven Sampling: Value 1 for Event 8 - // EVENT_VAL2_8 -Event Driven Sampling: Value 2 for Event 8 - // CHANNEL_FILTER -The channel filter for all channels - // MIN_SOFT_VER_MAJOR -The minimum software version for support of this device (major) - // MIN_SOFT_VER_MINOR -The minimum software version for support of this device (minor) - // - // THERMOCPL_TYPE -The thermocouple type for nodes with thermocouple capabilities (ie. TC-Link) - // FILTER_1 -The first filter value for nodes with filter capabilities (ie. TC-Link) - // FILTER_2 -The second filter value for nodes with 2 filter capabilities (ie. ENV-Link-Pro) + // CURRENT_LOG_PAGE -The next flash page to be used for datalogging + // CURRENT_PAGE_OFFSET -The byte offset location for the next datalogging session + // DATA_SETS_STORED -The # of datalogging sessions (triggers) stored in flash memory + // ACTIVE_CHANNEL_MASK -The channels that are enabled/disabled and will be sampled + // DATALOG_SAMPLE_RATE -The sample rate for Armed Datalogging sampling + // NUM_SWEEPS -The # of sweeps (samples per data set) to sample for + // DEFAULT_MODE -The default mode to allow the node to perform different operations on startup and after timeout + // SERIAL_ID -The serial ID for the node. Combine with the model number for the full serial number + // SAMPLING_MODE -The sampling mode of the node (Sync Sampling, Non-Sync Sampling, Armed Datalogging, etc.) + // HW_OFFSET_1 -The hardware offset of channel 1 + // HW_OFFSET_2 -The hardware offset of channel 2 + // HW_OFFSET_3 -The hardware offset of channel 3 + // HW_OFFSET_4 -The hardware offset of channel 4 + // HW_OFFSET_5 -The hardware offset of channel 5 + // HW_OFFSET_6 -The hardware offset of channel 6 + // HW_OFFSET_7 -The hardware offset of channel 7 + // HW_OFFSET_8 -The hardware offset of channel 8 + // SAMPLING_DELAY -The sampling delay (amount of time between sensor excitation power up and A/D sampling + // TDMA_ADDRESS -The TDMA network address used for Synchronized Sampling + // COLLECTION_MODE -The data collection mode (log, transmit) that affects standard sampling modes + // NUM_BUFF_PACKETS -The # of buffered packets + // NUM_RETRAN_ATTEMPTS -The # of retransmit attempts + // NODE_ADDRESS -The node address of the wireless node + // SLEEP_INTERVAL -The listen-for-wakeup interval for the node + // INACTIVE_TIMEOUT -The length of time necessary before a node enters sleep mode, if no user activity + // SAMPLE_RATE -The sample rate for standard sampling modes (Synchronized Sampling, LDC) + // DATA_FORMAT -The packet format (uint16, float, etc.) of sampled data + // SNIFF_DURATION -The amount of time that the node listens for a wake packets + // FREQUENCY -The radio frequency channel + // TX_POWER_LEVEL -The transmit output power of the radio + // UNLIMITED_SAMPLING -The unlimited sampling flag for standard sampling modes + // UNLIMITED_DATALOG -The unlimited sampling flag for Armed Datalogging sampling + // FIRMWARE_VER -The firmware version of the node (part 1) + // FIRMWARE_VER2 -The firmware version of the node (part 2) + // MODEL_NUMBER -The model number of the node + // MODEL_OPTION -The model option of the node + // LEGACY_MODEL_NUMBER -The (legacy) model number of the node + // LEGACY_SERIAL_ID -The (legacy) serial ID for the node. Combine with the model number for the full serial number + // MAX_MEMORY -The maximum number of pages available on the flash memory + // MICROCONTROLLER -The ID of the microcontroller + // FW_ARCH_VER -The firmware architecture version + // HW_GAIN_1 -The hardware gain of channel 1 + // HW_GAIN_2 -The hardware gain of channel 2 + // HW_GAIN_3 -The hardware gain of channel 3 + // HW_GAIN_4 -The hardware gain of channel 4 + // HW_GAIN_5 -The hardware gain of channel 5 + // HW_GAIN_6 -The hardware gain of channel 6 + // HW_GAIN_7 -The hardware gain of channel 7 + // HW_GAIN_8 -The hardware gain of channel 8 + // CH_ACTION_ID_1 -The channel action ID of channel 1 + // CH_ACTION_SLOPE_1 -The channel action slope of channel 1 + // CH_ACTION_OFFSET_1 -The channel action offset of channel 1 + // CH_ACTION_ID_2 -The channel action ID of channel 2 + // CH_ACTION_SLOPE_2 -The channel action slope of channel 2 + // CH_ACTION_OFFSET_2 -The channel action offset of channel 2 + // CH_ACTION_ID_3 -The channel action ID of channel 3 + // CH_ACTION_SLOPE_3 -The channel action slope of channel 3 + // CH_ACTION_OFFSET_3 -The channel action offset of channel 3 + // CH_ACTION_ID_4 -The channel action ID of channel 4 + // CH_ACTION_SLOPE_4 -The channel action slope of channel 4 + // CH_ACTION_OFFSET_4 -The channel action offset of channel 4 + // CH_ACTION_ID_5 -The channel action ID of channel 5 + // CH_ACTION_SLOPE_5 -The channel action slope of channel 5 + // CH_ACTION_OFFSET_5 -The channel action offset of channel 5 + // CH_ACTION_ID_6 -The channel action ID of channel 6 + // CH_ACTION_SLOPE_6 -The channel action slope of channel 6 + // CH_ACTION_OFFSET_6 -The channel action offset of channel 6 + // CH_ACTION_ID_7 -The channel action ID of channel 7 + // CH_ACTION_SLOPE_7 -The channel action slope of channel 7 + // CH_ACTION_OFFSET_7 -The channel action offset of channel 7 + // CH_ACTION_ID_8 -The channel action ID of channel 8 + // CH_ACTION_SLOPE_8 -The channel action slope of channel 8 + // CH_ACTION_OFFSET_8 -The channel action offset of channel 8 + // BOOTLOADER_VER -The bootloader version number + // RESET_COUNTER -The number of times the node has been turned on + // CYCLE_POWER -Used to soft reset the node or the radio on the node + // RADIO_OPTIONS -The options of the current radio (XR enabled or not, etc.) + // LOST_BEACON_TIMEOUT -The time for a node to wait before entering a low power state when no longer hearing a beacon in Sync Sampling + // SYNC_SAMPLE_SETTING -The Synchronized Sampling mode (Burst, Continuous, etc.) + // TX_PER_GROUP -The transmissions per group for Synchronized Sampling + // GROUP_SIZE -The group size for Synchronized Sampling + // TIME_BETW_SESSIONS -The time between each burst for Synchronized Sampling + // NODE_RETRANSMIT -Node retranmission enable/disable (for Lossless) + // MAX_RETRANS_PACKET -The max retransmits per packet + // MAX_RETRANS_BURST -The max retransmits per burst + // REGION_CODE -The region code for the device + // DATA_PACKET_FORMAT -The format of the data packet that will be sent out. + // EVENT_SAMPLE_RATE -Event Driven Sampling: Sample Rate + // EVENT_CHANNEL_MASK -Event Driven Sampling: Channel Mask + // EVENT_PRE_DURATION -Event Driven Sampling: Pre-Event Duration + // EVENT_POST_DURATION -Event Driven Sampling: Post-Event Duration + // EVENT_SRC_1 -Event Driven Sampling: The source for Event 1 + // EVENT_OPER_1 -Event Driven Sampling: The operation for Event 1 + // EVENT_VAL1_1 -Event Driven Sampling: Value 1 for Event 1 + // EVENT_VAL2_1 -Event Driven Sampling: Value 2 for Event 1 + // EVENT_SRC_2 -Event Driven Sampling: The source for Event 2 + // EVENT_OPER_2 -Event Driven Sampling: The operation for Event 2 + // EVENT_VAL1_2 -Event Driven Sampling: Value 1 for Event 2 + // EVENT_VAL2_2 -Event Driven Sampling: Value 2 for Event 2 + // EVENT_SRC_3 -Event Driven Sampling: The source for Event 3 + // EVENT_OPER_3 -Event Driven Sampling: The operation for Event 3 + // EVENT_VAL1_3 -Event Driven Sampling: Value 1 for Event 3 + // EVENT_VAL2_3 -Event Driven Sampling: Value 2 for Event 3 + // EVENT_SRC_4 -Event Driven Sampling: The source for Event 4 + // EVENT_OPER_4 -Event Driven Sampling: The operation for Event 4 + // EVENT_VAL1_4 -Event Driven Sampling: Value 1 for Event 4 + // EVENT_VAL2_4 -Event Driven Sampling: Value 2 for Event 4 + // EVENT_SRC_5 -Event Driven Sampling: The source for Event 5 + // EVENT_OPER_5 -Event Driven Sampling: The operation for Event 5 + // EVENT_VAL1_5 -Event Driven Sampling: Value 1 for Event 5 + // EVENT_VAL2_5 -Event Driven Sampling: Value 2 for Event 5 + // EVENT_SRC_6 -Event Driven Sampling: The source for Event 6 + // EVENT_OPER_6 -Event Driven Sampling: The operation for Event 6 + // EVENT_VAL1_6 -Event Driven Sampling: Value 1 for Event 6 + // EVENT_VAL2_6 -Event Driven Sampling: Value 2 for Event 6 + // EVENT_SRC_7 -Event Driven Sampling: The source for Event 7 + // EVENT_OPER_7 -Event Driven Sampling: The operation for Event 7 + // EVENT_VAL1_7 -Event Driven Sampling: Value 1 for Event 7 + // EVENT_VAL2_7 -Event Driven Sampling: Value 2 for Event 7 + // EVENT_SRC_8 -Event Driven Sampling: The source for Event 8 + // EVENT_OPER_8 -Event Driven Sampling: The operation for Event 8 + // EVENT_VAL1_8 -Event Driven Sampling: Value 1 for Event 8 + // EVENT_VAL2_8 -Event Driven Sampling: Value 2 for Event 8 + // CHANNEL_FILTER -The channel filter for all channels + // MIN_SOFT_VER_MAJOR -The minimum software version for support of this device (major) + // MIN_SOFT_VER_MINOR -The minimum software version for support of this device (minor) + // GAUGE_FACTOR_1 -The Gauge Factor (1) + // GAUGE_FACTOR_2 -The Gauge Factor (2) + // GAUGE_FACTOR_3 -The Gauge Factor (3) + // GAUGE_FACTOR_4 -The Gauge Factor (4) + // + // THERMOCPL_TYPE -The thermocouple type for nodes with thermocouple capabilities (ie. TC-Link) + // FILTER_1 -The first filter value for nodes with filter capabilities (ie. TC-Link) + // FILTER_2 -The second filter value for nodes with 2 filter capabilities (ie. ENV-Link-Pro) + + // LEGACY_DAMAGE_ANGLE_1 -The first damage angle (legacy). + // LEGACY_DAMAGE_ANGLE_2 -The second damage angle (legacy). + // LEGACY_DAMAGE_ANGLE_3 -The third damage angle (legacy). + // BIN_SIZE -The size of each bin in the histogram. + // RESET_BINS -Used to reset the histogram bin data. + // BIN_START -The start of the bins. + // PEAK_VALLEY_THRES -The peak/valley threshold. + // SNCURVE_LOGA_1 -logA of the first SN Curve. + // SNCURVE_M_1 -m of the first SN Curve. + // SNCURVE_LOGA_2 -logA of the second SN Curve. + // SNCURVE_M_2 -m of the second SN Curve. + // SNCURVE_LOGA_3 -logA of the third SN Curve. + // SNCURVE_M_3 -m of the third SN Curve. + // YOUNGS_MODULUS -The youngs modulus. + // POISSONS_RATIO -The poissons ratio. + // HISTOGRAM_SAMPLE_RATE -The same rate of the histogram. + // DAMAGE_ANGLE_1 -The first damage angle. + // DAMAGE_ANGLE_2 -The second damage angle. + // DAMAGE_ANGLE_3 -The third damage angle. + // FATIGUE_MODE -SHM 3-angle mode vs Distributed Angle mode vs Raw Gauge Strain mode. + // DIST_ANGLE_NUM_ANGLES -The number of angles for Distributed Angle Mode. + // DIST_ANGLE_LOWER_BOUND -The lower bound for Distributed Angle Mode. + // DIST_ANGLE_UPPER_BOUND -The upper bound for Distributed Angle Mode. + + // HISTOGRAM_RAW_FLAG -Raw mode enable/disable. + // ACT_SENSE_ENABLE -Activity Sense enable/disable. + // ACT_SENSE_ACTIVE_THRES -Activity Sense activity threshold. + // ACT_SENSE_INACTIVE_TIMEOUT -Activity Sense inactivity timeout. + // ACT_SENSE_ACTIVE_TIME -Activity Sense activity time. + // ACT_SENSE_INACTIVE_THRES -Activity Sense inactivity threshold. + // HISTOGRAM_ENABLE -Histogram enable/disable. //======================================================================================================================= - static const EepromLocation CURRENT_LOG_PAGE; //The next flash page to be used for datalogging - static const EepromLocation CURRENT_PAGE_OFFSET; //The byte offset location for the next datalogging session - static const EepromLocation DATA_SETS_STORED; //The # of datalogging sessions (triggers) stored in flash memory - static const EepromLocation ACTIVE_CHANNEL_MASK; //The channels that are enabled/disabled and will be sampled - static const EepromLocation DATALOG_SAMPLE_RATE; //The sample rate for Armed Datalogging sampling - static const EepromLocation NUM_SWEEPS; //The # of sweeps (samples per data set) to sample for - static const EepromLocation DEFAULT_MODE; //The default mode to allow the node to perform different operations on startup and after timeout - static const EepromLocation SERIAL_ID; //The serial ID for the node. Combine with the model number for the full serial number - static const EepromLocation SAMPLING_MODE; //The sampling mode of the node (Sync Sampling, Non-Sync Sampling, Armed Datalogging, etc.) - static const EepromLocation HW_OFFSET_1; //The hardware offset of channel 1 - static const EepromLocation HW_OFFSET_2; //The hardware offset of channel 2 - static const EepromLocation HW_OFFSET_3; //The hardware offset of channel 3 - static const EepromLocation HW_OFFSET_4; //The hardware offset of channel 4 - static const EepromLocation HW_OFFSET_5; //The hardware offset of channel 5 - static const EepromLocation HW_OFFSET_6; //The hardware offset of channel 6 - static const EepromLocation HW_OFFSET_7; //The hardware offset of channel 7 - static const EepromLocation HW_OFFSET_8; //The hardware offset of channel 8 - static const EepromLocation SAMPLING_DELAY; //The sampling delay (amount of time between sensor excitation power up and A/D sampling) - static const EepromLocation TDMA_ADDRESS; //The TDMA network address used for Synchronized Sampling - static const EepromLocation COLLECTION_MODE; //The data collection mode (log, transmit) that affects standard sampling modes - static const EepromLocation NUM_BUFF_PACKETS; //The # of buffered packets - static const EepromLocation NUM_RETRAN_ATTEMPTS; //The # of retransmit attempts - static const EepromLocation NODE_ADDRESS; //The node address of the wireless node - static const EepromLocation SLEEP_INTERVAL; //The listen-for-wakeup interval for the node - static const EepromLocation INACTIVE_TIMEOUT; //The length of time necessary before a node enters sleep mode, if no user activity - static const EepromLocation SAMPLE_RATE; //The sample rate for standard sampling modes (Synchronized Sampling, LDC) - static const EepromLocation DATA_FORMAT; //The packet format (uint16, float, etc.) of sampled data - static const EepromLocation SNIFF_DURATION; //The amount of time that the node listens for a wake packets - static const EepromLocation FREQUENCY; //The radio frequency channel - static const EepromLocation TX_POWER_LEVEL; //The transmit output power of the radio - static const EepromLocation UNLIMITED_SAMPLING; //The unlimited sampling flag for standard sampling modes - static const EepromLocation UNLIMITED_DATALOG; //The unlimited sampling flag for Armed Datalogging sampling - static const EepromLocation FIRMWARE_VER; //The firmware version of the node (part 1) - static const EepromLocation FIRMWARE_VER2; //The firmware version of the node (part 2) - static const EepromLocation MODEL_NUMBER; //The model number of the node - static const EepromLocation MODEL_OPTION; //The model option of the node - static const EepromLocation LEGACY_MODEL_NUMBER; //The (legacy) model number of the node - static const EepromLocation LEGACY_SERIAL_ID; //The (legacy) serial ID for the node. Combine with the model number for the full serial number - static const EepromLocation MAX_MEMORY; //The maximum number of pages available on the flash memory - static const EepromLocation MICROCONTROLLER; //The ID of the microcontroller - static const EepromLocation FW_ARCH_VER; //The firmware architecture version - static const EepromLocation HW_GAIN_1; //The hardware gain of channel 1 - static const EepromLocation HW_GAIN_2; //The hardware gain of channel 2 - static const EepromLocation HW_GAIN_3; //The hardware gain of channel 3 - static const EepromLocation HW_GAIN_4; //The hardware gain of channel 4 - static const EepromLocation CH_ACTION_ID_1; //The channel action ID of channel 1 - static const EepromLocation CH_ACTION_SLOPE_1; //The channel action slope of channel 1 - static const EepromLocation CH_ACTION_OFFSET_1; //The channel action offset of channel 1 - static const EepromLocation CH_ACTION_ID_2; //The channel action ID of channel 2 - static const EepromLocation CH_ACTION_SLOPE_2; //The channel action slope of channel 2 - static const EepromLocation CH_ACTION_OFFSET_2; //The channel action offset of channel 2 - static const EepromLocation CH_ACTION_ID_3; //The channel action ID of channel 3 - static const EepromLocation CH_ACTION_SLOPE_3; //The channel action slope of channel 3 - static const EepromLocation CH_ACTION_OFFSET_3; //The channel action offset of channel 3 - static const EepromLocation CH_ACTION_ID_4; //The channel action ID of channel 4 - static const EepromLocation CH_ACTION_SLOPE_4; //The channel action slope of channel 4 - static const EepromLocation CH_ACTION_OFFSET_4; //The channel action offset of channel 4 - static const EepromLocation CH_ACTION_ID_5; //The channel action ID of channel 5 - static const EepromLocation CH_ACTION_SLOPE_5; //The channel action slope of channel 5 - static const EepromLocation CH_ACTION_OFFSET_5; //The channel action offset of channel 5 - static const EepromLocation CH_ACTION_ID_6; //The channel action ID of channel 6 - static const EepromLocation CH_ACTION_SLOPE_6; //The channel action slope of channel 6 - static const EepromLocation CH_ACTION_OFFSET_6; //The channel action offset of channel 6 - static const EepromLocation CH_ACTION_ID_7; //The channel action ID of channel 7 - static const EepromLocation CH_ACTION_SLOPE_7; //The channel action slope of channel 7 - static const EepromLocation CH_ACTION_OFFSET_7; //The channel action offset of channel 7 - static const EepromLocation CH_ACTION_ID_8; //The channel action ID of channel 8 - static const EepromLocation CH_ACTION_SLOPE_8; //The channel action slope of channel 8 - static const EepromLocation CH_ACTION_OFFSET_8; //The channel action offset of channel 8 - static const EepromLocation BOOTLOADER_VER; //The bootloader version number - static const EepromLocation RESET_COUNTER; //The number of times the node has been turned on - static const EepromLocation CYCLE_POWER; //Used to soft reset the node or the radio on the node - static const EepromLocation RADIO_OPTIONS; //The options of the current radio (XR enabled or not, etc.) - static const EepromLocation LOST_BEACON_TIMEOUT; //The time for a node to wait before entering a low power state when no longer hearing a beacon in Sync Sampling - static const EepromLocation SYNC_SAMPLE_SETTING; //The Synchronized Sampling mode (Burst, Continuous, etc.) - static const EepromLocation TX_PER_GROUP; //The transmissions per group for Synchronized Sampling - static const EepromLocation GROUP_SIZE; //The group size for Synchronized Sampling - static const EepromLocation TIME_BETW_SESSIONS; //The time between each burst for Synchronized Sampling - static const EepromLocation NODE_RETRANSMIT; //Node retranmission enable/disable (for Lossless) - static const EepromLocation MAX_RETRANS_PACKET; //The max retransmits per packet - static const EepromLocation MAX_RETRANS_BURST; //The max retransmits per burst - static const EepromLocation REGION_CODE; //The region code for the device. - static const EepromLocation EVENT_SAMPLE_RATE; //Event Driven Sampling: Sample Rate - static const EepromLocation EVENT_CHANNEL_MASK; //Event Driven Sampling: Channel Mask - static const EepromLocation EVENT_PRE_DURATION; //Event Driven Sampling: Pre-Event Duration - static const EepromLocation EVENT_POST_DURATION; //Event Driven Sampling: Post-Event Duration - static const EepromLocation EVENT_SRC_1; //Event Driven Sampling: The source for Event 1 - static const EepromLocation EVENT_OPER_1; //Event Driven Sampling: The operation for Event 1 - static const EepromLocation EVENT_VAL1_1; //Event Driven Sampling: Value 1 for Event 1 - static const EepromLocation EVENT_VAL2_1; //Event Driven Sampling: Value 2 for Event 1 - static const EepromLocation EVENT_SRC_2 ; //Event Driven Sampling: The source for Event 2 - static const EepromLocation EVENT_OPER_2; //Event Driven Sampling: The operation for Event 2 - static const EepromLocation EVENT_VAL1_2; //Event Driven Sampling: Value 1 for Event 2 - static const EepromLocation EVENT_VAL2_2; //Event Driven Sampling: Value 2 for Event 2 - static const EepromLocation EVENT_SRC_3 ; //Event Driven Sampling: The source for Event 3 - static const EepromLocation EVENT_OPER_3; //Event Driven Sampling: The operation for Event 3 - static const EepromLocation EVENT_VAL1_3; //Event Driven Sampling: Value 1 for Event 3 - static const EepromLocation EVENT_VAL2_3; //Event Driven Sampling: Value 2 for Event 3 - static const EepromLocation EVENT_SRC_4 ; //Event Driven Sampling: The source for Event 4 - static const EepromLocation EVENT_OPER_4; //Event Driven Sampling: The operation for Event 4 - static const EepromLocation EVENT_VAL1_4; //Event Driven Sampling: Value 1 for Event 4 - static const EepromLocation EVENT_VAL2_4; //Event Driven Sampling: Value 2 for Event 4 - static const EepromLocation EVENT_SRC_5 ; //Event Driven Sampling: The source for Event 5 - static const EepromLocation EVENT_OPER_5; //Event Driven Sampling: The operation for Event 5 - static const EepromLocation EVENT_VAL1_5; //Event Driven Sampling: Value 1 for Event 5 - static const EepromLocation EVENT_VAL2_5; //Event Driven Sampling: Value 2 for Event 5 - static const EepromLocation EVENT_SRC_6 ; //Event Driven Sampling: The source for Event 6 - static const EepromLocation EVENT_OPER_6; //Event Driven Sampling: The operation for Event 6 - static const EepromLocation EVENT_VAL1_6; //Event Driven Sampling: Value 1 for Event 6 - static const EepromLocation EVENT_VAL2_6; //Event Driven Sampling: Value 2 for Event 6 - static const EepromLocation EVENT_SRC_7 ; //Event Driven Sampling: The source for Event 7 - static const EepromLocation EVENT_OPER_7; //Event Driven Sampling: The operation for Event 7 - static const EepromLocation EVENT_VAL1_7; //Event Driven Sampling: Value 1 for Event 7 - static const EepromLocation EVENT_VAL2_7; //Event Driven Sampling: Value 2 for Event 7 - static const EepromLocation EVENT_SRC_8 ; //Event Driven Sampling: The source for Event 8 - static const EepromLocation EVENT_OPER_8; //Event Driven Sampling: The operation for Event 8 - static const EepromLocation EVENT_VAL1_8; //Event Driven Sampling: Value 1 for Event 8 - static const EepromLocation EVENT_VAL2_8; //Event Driven Sampling: Value 2 for Event 8 - static const EepromLocation CHANNEL_FILTER; //The channel filter for all channels - static const EepromLocation MIN_SOFT_VER_MAJOR; //The minimum software version for support of this device (major). - static const EepromLocation MIN_SOFT_VER_MINOR; //The minimum software version for support of this device (minor). + static const EepromLocation CURRENT_LOG_PAGE; //The next flash page to be used for datalogging + static const EepromLocation CURRENT_PAGE_OFFSET; //The byte offset location for the next datalogging session + static const EepromLocation DATA_SETS_STORED; //The # of datalogging sessions (triggers) stored in flash memory + static const EepromLocation ACTIVE_CHANNEL_MASK; //The channels that are enabled/disabled and will be sampled + static const EepromLocation DATALOG_SAMPLE_RATE; //The sample rate for Armed Datalogging sampling + static const EepromLocation NUM_SWEEPS; //The # of sweeps (samples per data set) to sample for + static const EepromLocation DEFAULT_MODE; //The default mode to allow the node to perform different operations on startup and after timeout + static const EepromLocation SERIAL_ID; //The serial ID for the node. Combine with the model number for the full serial number + static const EepromLocation SAMPLING_MODE; //The sampling mode of the node (Sync Sampling, Non-Sync Sampling, Armed Datalogging, etc.) + static const EepromLocation HW_OFFSET_1; //The hardware offset of channel 1 + static const EepromLocation HW_OFFSET_2; //The hardware offset of channel 2 + static const EepromLocation HW_OFFSET_3; //The hardware offset of channel 3 + static const EepromLocation HW_OFFSET_4; //The hardware offset of channel 4 + static const EepromLocation HW_OFFSET_5; //The hardware offset of channel 5 + static const EepromLocation HW_OFFSET_6; //The hardware offset of channel 6 + static const EepromLocation HW_OFFSET_7; //The hardware offset of channel 7 + static const EepromLocation HW_OFFSET_8; //The hardware offset of channel 8 + static const EepromLocation SAMPLING_DELAY; //The sampling delay (amount of time between sensor excitation power up and A/D sampling) + static const EepromLocation TDMA_ADDRESS; //The TDMA network address used for Synchronized Sampling + static const EepromLocation COLLECTION_MODE; //The data collection mode (log, transmit) that affects standard sampling modes + static const EepromLocation NUM_BUFF_PACKETS; //The # of buffered packets + static const EepromLocation NUM_RETRAN_ATTEMPTS; //The # of retransmit attempts + static const EepromLocation NODE_ADDRESS; //The node address of the wireless node + static const EepromLocation SLEEP_INTERVAL; //The listen-for-wakeup interval for the node + static const EepromLocation INACTIVE_TIMEOUT; //The length of time necessary before a node enters sleep mode, if no user activity + static const EepromLocation SAMPLE_RATE; //The sample rate for standard sampling modes (Synchronized Sampling, LDC) + static const EepromLocation DATA_FORMAT; //The packet format (uint16, float, etc.) of sampled data + static const EepromLocation SNIFF_DURATION; //The amount of time that the node listens for a wake packets + static const EepromLocation FREQUENCY; //The radio frequency channel + static const EepromLocation TX_POWER_LEVEL; //The transmit output power of the radio + static const EepromLocation UNLIMITED_SAMPLING; //The unlimited sampling flag for standard sampling modes + static const EepromLocation UNLIMITED_DATALOG; //The unlimited sampling flag for Armed Datalogging sampling + static const EepromLocation FIRMWARE_VER; //The firmware version of the node (part 1) + static const EepromLocation FIRMWARE_VER2; //The firmware version of the node (part 2) + static const EepromLocation MODEL_NUMBER; //The model number of the node + static const EepromLocation MODEL_OPTION; //The model option of the node + static const EepromLocation LEGACY_MODEL_NUMBER; //The (legacy) model number of the node + static const EepromLocation LEGACY_SERIAL_ID; //The (legacy) serial ID for the node. Combine with the model number for the full serial number + static const EepromLocation MAX_MEMORY; //The maximum number of pages available on the flash memory + static const EepromLocation MICROCONTROLLER; //The ID of the microcontroller + static const EepromLocation FW_ARCH_VER; //The firmware architecture version + static const EepromLocation HW_GAIN_1; //The hardware gain of channel 1 + static const EepromLocation HW_GAIN_2; //The hardware gain of channel 2 + static const EepromLocation HW_GAIN_3; //The hardware gain of channel 3 + static const EepromLocation HW_GAIN_4; //The hardware gain of channel 4 + static const EepromLocation CH_ACTION_ID_1; //The channel action ID of channel 1 + static const EepromLocation CH_ACTION_SLOPE_1; //The channel action slope of channel 1 + static const EepromLocation CH_ACTION_OFFSET_1; //The channel action offset of channel 1 + static const EepromLocation CH_ACTION_ID_2; //The channel action ID of channel 2 + static const EepromLocation CH_ACTION_SLOPE_2; //The channel action slope of channel 2 + static const EepromLocation CH_ACTION_OFFSET_2; //The channel action offset of channel 2 + static const EepromLocation CH_ACTION_ID_3; //The channel action ID of channel 3 + static const EepromLocation CH_ACTION_SLOPE_3; //The channel action slope of channel 3 + static const EepromLocation CH_ACTION_OFFSET_3; //The channel action offset of channel 3 + static const EepromLocation CH_ACTION_ID_4; //The channel action ID of channel 4 + static const EepromLocation CH_ACTION_SLOPE_4; //The channel action slope of channel 4 + static const EepromLocation CH_ACTION_OFFSET_4; //The channel action offset of channel 4 + static const EepromLocation CH_ACTION_ID_5; //The channel action ID of channel 5 + static const EepromLocation CH_ACTION_SLOPE_5; //The channel action slope of channel 5 + static const EepromLocation CH_ACTION_OFFSET_5; //The channel action offset of channel 5 + static const EepromLocation CH_ACTION_ID_6; //The channel action ID of channel 6 + static const EepromLocation CH_ACTION_SLOPE_6; //The channel action slope of channel 6 + static const EepromLocation CH_ACTION_OFFSET_6; //The channel action offset of channel 6 + static const EepromLocation CH_ACTION_ID_7; //The channel action ID of channel 7 + static const EepromLocation CH_ACTION_SLOPE_7; //The channel action slope of channel 7 + static const EepromLocation CH_ACTION_OFFSET_7; //The channel action offset of channel 7 + static const EepromLocation CH_ACTION_ID_8; //The channel action ID of channel 8 + static const EepromLocation CH_ACTION_SLOPE_8; //The channel action slope of channel 8 + static const EepromLocation CH_ACTION_OFFSET_8; //The channel action offset of channel 8 + static const EepromLocation BOOTLOADER_VER; //The bootloader version number + static const EepromLocation RESET_COUNTER; //The number of times the node has been turned on + static const EepromLocation CYCLE_POWER; //Used to soft reset the node or the radio on the node + static const EepromLocation RADIO_OPTIONS; //The options of the current radio (XR enabled or not, etc.) + static const EepromLocation LOST_BEACON_TIMEOUT; //The time for a node to wait before entering a low power state when no longer hearing a beacon in Sync Sampling + static const EepromLocation SYNC_SAMPLE_SETTING; //The Synchronized Sampling mode (Burst, Continuous, etc.) + static const EepromLocation TX_PER_GROUP; //The transmissions per group for Synchronized Sampling + static const EepromLocation GROUP_SIZE; //The group size for Synchronized Sampling + static const EepromLocation TIME_BETW_SESSIONS; //The time between each burst for Synchronized Sampling + static const EepromLocation NODE_RETRANSMIT; //Node retranmission enable/disable (for Lossless) + static const EepromLocation MAX_RETRANS_PACKET; //The max retransmits per packet + static const EepromLocation MAX_RETRANS_BURST; //The max retransmits per burst + static const EepromLocation REGION_CODE; //The region code for the device. + static const EepromLocation DATA_PACKET_FORMAT; //The format of the data packets that will sent out. + static const EepromLocation EVENT_SAMPLE_RATE; //Event Driven Sampling: Sample Rate + static const EepromLocation EVENT_CHANNEL_MASK; //Event Driven Sampling: Channel Mask + static const EepromLocation EVENT_PRE_DURATION; //Event Driven Sampling: Pre-Event Duration + static const EepromLocation EVENT_POST_DURATION; //Event Driven Sampling: Post-Event Duration + static const EepromLocation EVENT_SRC_1; //Event Driven Sampling: The source for Event 1 + static const EepromLocation EVENT_OPER_1; //Event Driven Sampling: The operation for Event 1 + static const EepromLocation EVENT_VAL1_1; //Event Driven Sampling: Value 1 for Event 1 + static const EepromLocation EVENT_VAL2_1; //Event Driven Sampling: Value 2 for Event 1 + static const EepromLocation EVENT_SRC_2 ; //Event Driven Sampling: The source for Event 2 + static const EepromLocation EVENT_OPER_2; //Event Driven Sampling: The operation for Event 2 + static const EepromLocation EVENT_VAL1_2; //Event Driven Sampling: Value 1 for Event 2 + static const EepromLocation EVENT_VAL2_2; //Event Driven Sampling: Value 2 for Event 2 + static const EepromLocation EVENT_SRC_3 ; //Event Driven Sampling: The source for Event 3 + static const EepromLocation EVENT_OPER_3; //Event Driven Sampling: The operation for Event 3 + static const EepromLocation EVENT_VAL1_3; //Event Driven Sampling: Value 1 for Event 3 + static const EepromLocation EVENT_VAL2_3; //Event Driven Sampling: Value 2 for Event 3 + static const EepromLocation EVENT_SRC_4 ; //Event Driven Sampling: The source for Event 4 + static const EepromLocation EVENT_OPER_4; //Event Driven Sampling: The operation for Event 4 + static const EepromLocation EVENT_VAL1_4; //Event Driven Sampling: Value 1 for Event 4 + static const EepromLocation EVENT_VAL2_4; //Event Driven Sampling: Value 2 for Event 4 + static const EepromLocation EVENT_SRC_5 ; //Event Driven Sampling: The source for Event 5 + static const EepromLocation EVENT_OPER_5; //Event Driven Sampling: The operation for Event 5 + static const EepromLocation EVENT_VAL1_5; //Event Driven Sampling: Value 1 for Event 5 + static const EepromLocation EVENT_VAL2_5; //Event Driven Sampling: Value 2 for Event 5 + static const EepromLocation EVENT_SRC_6 ; //Event Driven Sampling: The source for Event 6 + static const EepromLocation EVENT_OPER_6; //Event Driven Sampling: The operation for Event 6 + static const EepromLocation EVENT_VAL1_6; //Event Driven Sampling: Value 1 for Event 6 + static const EepromLocation EVENT_VAL2_6; //Event Driven Sampling: Value 2 for Event 6 + static const EepromLocation EVENT_SRC_7 ; //Event Driven Sampling: The source for Event 7 + static const EepromLocation EVENT_OPER_7; //Event Driven Sampling: The operation for Event 7 + static const EepromLocation EVENT_VAL1_7; //Event Driven Sampling: Value 1 for Event 7 + static const EepromLocation EVENT_VAL2_7; //Event Driven Sampling: Value 2 for Event 7 + static const EepromLocation EVENT_SRC_8 ; //Event Driven Sampling: The source for Event 8 + static const EepromLocation EVENT_OPER_8; //Event Driven Sampling: The operation for Event 8 + static const EepromLocation EVENT_VAL1_8; //Event Driven Sampling: Value 1 for Event 8 + static const EepromLocation EVENT_VAL2_8; //Event Driven Sampling: Value 2 for Event 8 + static const EepromLocation CHANNEL_FILTER; //The channel filter for all channels + static const EepromLocation MIN_SOFT_VER_MAJOR; //The minimum software version for support of this device (major). + static const EepromLocation MIN_SOFT_VER_MINOR; //The minimum software version for support of this device (minor). + static const EepromLocation GAUGE_FACTOR_1; //The Gauge Factor (1). + static const EepromLocation GAUGE_FACTOR_2; //The Gauge Factor (2). + static const EepromLocation GAUGE_FACTOR_3; //The Gauge Factor (3). + static const EepromLocation GAUGE_FACTOR_4; //The Gauge Factor (4). + + static const EepromLocation THERMOCPL_TYPE; //The thermocouple type for nodes with thermocouple capabilities (ie. TC-Link) + static const EepromLocation FILTER_1; //The first filter value for nodes with filter capabilities (ie. TC-Link) + static const EepromLocation FILTER_2; //The second filter value for nodes with 2 filter capabilities (ie. ENV-Link-Pro) + + static const EepromLocation LEGACY_DAMAGE_ANGLE_1; //The first damage angle (legacy). + static const EepromLocation LEGACY_DAMAGE_ANGLE_2; //The second damage angle (legacy). + static const EepromLocation LEGACY_DAMAGE_ANGLE_3; //The third damage angle (legacy). + static const EepromLocation BIN_SIZE; //The size of each bin in the histogram. + static const EepromLocation RESET_BINS; //Used to reset the histogram bin data. + static const EepromLocation BIN_START; //The start of the bins. + static const EepromLocation PEAK_VALLEY_THRES; //The peak/valley threshold. + static const EepromLocation SNCURVE_LOGA_1; //logA of the first SN Curve. + static const EepromLocation SNCURVE_M_1; //m of the first SN Curve. + static const EepromLocation SNCURVE_LOGA_2; //logA of the second SN Curve. + static const EepromLocation SNCURVE_M_2; //m of the second SN Curve. + static const EepromLocation SNCURVE_LOGA_3; //logA of the third SN Curve. + static const EepromLocation SNCURVE_M_3; //m of the third SN Curve. + static const EepromLocation YOUNGS_MODULUS; //The youngs modulus. + static const EepromLocation POISSONS_RATIO; //The poissons ratio. + static const EepromLocation HISTOGRAM_SAMPLE_RATE; //The same rate of the histogram. + static const EepromLocation DAMAGE_ANGLE_1; //The first damage angle. + static const EepromLocation DAMAGE_ANGLE_2; //The second damage angle. + static const EepromLocation DAMAGE_ANGLE_3; //The third damage angle. + static const EepromLocation FATIGUE_MODE; //Fatigue 3-angle mode vs Distributed Angle mode vs Raw Gauge Strain mode. + static const EepromLocation DIST_ANGLE_NUM_ANGLES; //The number of angles for Distributed Angle Mode. + static const EepromLocation DIST_ANGLE_LOWER_BOUND; //The lower bound for Distributed Angle Mode. + static const EepromLocation DIST_ANGLE_UPPER_BOUND; //The upper bound for Distributed Angle Mode. + static const EepromLocation HISTOGRAM_RAW_FLAG; //Raw mode enable/disable. + static const EepromLocation ACT_SENSE_ENABLE; //Activity Sense enable/disable. + static const EepromLocation ACT_SENSE_ACTIVE_THRES; //Activity Sense activity threshold. + static const EepromLocation ACT_SENSE_INACTIVE_TIMEOUT; //Activity Sense inactivity timeout. + static const EepromLocation ACT_SENSE_ACTIVE_TIME; //Activity Sense activity time. + static const EepromLocation ACT_SENSE_INACTIVE_THRES; //Activity Sense inactivity threshold. + static const EepromLocation HISTOGRAM_ENABLE; //Histogram enable/disable. - static const EepromLocation THERMOCPL_TYPE; //The thermocouple type for nodes with thermocouple capabilities (ie. TC-Link) - static const EepromLocation FILTER_1; //The first filter value for nodes with filter capabilities (ie. TC-Link) - static const EepromLocation FILTER_2; //The second filter value for nodes with 2 filter capabilities (ie. ENV-Link-Pro) - - static const EepromLocation DAMAGE_ANGLE_1; - static const EepromLocation DAMAGE_ANGLE_2; - static const EepromLocation DAMAGE_ANGLE_3; - static const EepromLocation LEGACY_DAMAGE_ANGLE_1; - static const EepromLocation LEGACY_DAMAGE_ANGLE_2; - static const EepromLocation LEGACY_DAMAGE_ANGLE_3; - static const EepromLocation BIN_SIZE; - static const EepromLocation RESET_BINS; - static const EepromLocation BIN_START; - static const EepromLocation PEAK_VALLEY_THRES; - static const EepromLocation SNCURVE_LOGA_1; - static const EepromLocation SNCURVE_M_1; - static const EepromLocation SNCURVE_LOGA_2; - static const EepromLocation SNCURVE_M_2; - static const EepromLocation SNCURVE_LOGA_3; - static const EepromLocation SNCURVE_M_3; - static const EepromLocation YOUNGS_MODULUS; - static const EepromLocation POISSONS_RATIO; - static const EepromLocation HISTOGRAM_SAMPLE_RATE; - static const EepromLocation HISTOGRAM_RAW_FLAG; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/WirelessNodeConfig.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/WirelessNodeConfig.cpp index 06173e8a9..5ce7df2b5 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/WirelessNodeConfig.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/WirelessNodeConfig.cpp @@ -154,14 +154,29 @@ namespace mscl //Number of Sweeps if(isSet(m_numSweeps)) - { + { + //verify that we supported setting num sweeps + if(!features.supportsLimitedDuration()) + { + outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_SWEEPS, "Number of Sweeps is not supported by this Node.")); + } //verify the sweeps are normalized - if(*m_numSweeps != features.normalizeNumSweeps(*m_numSweeps)) + else if(*m_numSweeps != features.normalizeNumSweeps(*m_numSweeps)) { outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_SWEEPS, "The number of Sweeps needs to be normalized.")); } } + //Unlimited Duration + if(isSet(m_unlimitedDuration)) + { + //if the node only supports unlimited duration and the user turned it off + if(!features.supportsLimitedDuration() && (*m_unlimitedDuration == false)) + { + outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_UNLIMITED_DURATION, "Unlimited duration cannot be disabled for this Node.")); + } + } + //Data Format if(isSet(m_dataFormat)) { @@ -202,10 +217,15 @@ namespace mscl { uint16 val = *m_lostBeaconTimeout; + //verify lost beacon timeout is supported + if(!features.supportsLostBeaconTimeout()) + { + outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_LOST_BEACON_TIMEOUT, "Lost Beacon Timeout is not supported by this Node.")); + } //verify the timeout is within range - if((val < features.minLostBeaconTimeout() && val != NodeEepromHelper::LOST_BEACON_TIMEOUT_DISABLED) || - val > features.maxLostBeaconTimeout() - ) + else if((val < features.minLostBeaconTimeout() && val != NodeEepromHelper::LOST_BEACON_TIMEOUT_DISABLED) || + val > features.maxLostBeaconTimeout() + ) { outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_LOST_BEACON_TIMEOUT, "The Lost Beacon Timeout value is out of range.")); } @@ -237,7 +257,7 @@ namespace mscl { if(angle.first > maxAngle) { - outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_FATIGUE, "Damage Angle ID " + Utils::toStr(angle.first) + " is not supported by this Node.")); + outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_FATIGUE_ANGLE_ID, "Damage Angle ID " + Utils::toStr(angle.first) + " is not supported by this Node.")); } } @@ -247,7 +267,37 @@ namespace mscl { if(segment.first > maxSegment) { - outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_FATIGUE, "SN Curve Segment " + Utils::toStr(segment.first) + " is not supported by this Node.")); + outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_FATIGUE_SN_CURVE, "SN Curve Segment " + Utils::toStr(segment.first) + " is not supported by this Node.")); + } + } + + //if we plan on writing the fatigue mode + if(features.supportsFatigueModeConfig()) + { + //check the fatigue mode is supported + if(!features.supportsFatigueMode(m_fatigueOptions->fatigueMode())) + { + outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_FATIGUE_MODE, "The Fatigue Mode is not supported by this Node.")); + } + } + + //if we plan on writing distributed angle mode settings + if(features.supportsFatigueMode(WirelessTypes::fatigueMode_distributedAngle)) + { + //check for distributed angle mode invalid number of angles + uint8 numAngles = m_fatigueOptions->distributedAngleMode_numAngles(); + if(numAngles < 4 || numAngles > 16) + { + outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_FATIGUE_DIST_NUM_ANGLES, "Number of Distributed Angles is out of range (4-16).")); + } + + //check if upper and lower bounds are within 1 degree + float diff = std::abs(m_fatigueOptions->distributedAngleMode_upperBound() - m_fatigueOptions->distributedAngleMode_lowerBound()); + bool lowGreaterThanUpper = m_fatigueOptions->distributedAngleMode_upperBound() < m_fatigueOptions->distributedAngleMode_lowerBound(); + + if(diff < 1.0f || (lowGreaterThanUpper && diff > 359.0f)) + { + outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_FATIGUE_DIST_ANGLE, "Lower and Upper Distributed Angle bounds cannot be within 1 degree of each other.")); } } } @@ -268,11 +318,21 @@ namespace mscl //check the tx rate is supported if(std::find(txRates.begin(), txRates.end(), m_histogramOptions->transmitRate()) == txRates.end()) { - outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_HISTOGRAM, "The Histogram Transmit Rate is not supported by this Node.")); + outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_HISTOGRAM_TX_RATE, "The Histogram Transmit Rate is not supported by this Node.")); } } } + //Activity Sense + if(isSet(m_activitySense)) + { + //check that ActivitySense is supported + if(!features.supportsActivitySense()) + { + outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_ACTIVITY_SENSE, "ActivitySense configuration is not supported by this Node.")); + } + } + //Hardware Gain(s) for(const auto& gain : m_hardwareGains) { @@ -298,6 +358,16 @@ namespace mscl } } + //Gauge Factors + for(const auto& factor : m_gaugeFactors) + { + //verify gauge factor is supported for the channel mask + if(!features.supportsChannelSetting(WirelessTypes::chSetting_gaugeFactor, factor.first)) + { + outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_GAUGE_FACTOR, "Gauge Factor is not supported for the provided Channel Mask.", factor.first)); + } + } + //Linear Equation(s) for(const auto& eq : m_linearEquations) { @@ -384,18 +454,21 @@ namespace mscl } } - if(isSet(m_numSweeps) || isSet(m_samplingMode) || isSet(m_dataFormat) || isSet(m_activeChannels)) + if(features.supportsLimitedDuration()) { - bool unlimitedDuration = curUnlimitedDuration(eeprom); - - //don't check if unlimited duration - //unless sampling mode is burst, which ignores unlimited duration - if(!unlimitedDuration || samplingMode == WirelessTypes::samplingMode_syncBurst) + if(isSet(m_numSweeps) || isSet(m_samplingMode) || isSet(m_dataFormat) || isSet(m_activeChannels)) { - //verify the number of sweeps works with the other sampling settings - if(numSweeps > features.maxSweeps(samplingMode, dataFormat, channels)) + bool unlimitedDuration = curUnlimitedDuration(eeprom); + + //don't check if unlimited duration + //unless sampling mode is burst, which ignores unlimited duration + if(!unlimitedDuration || samplingMode == WirelessTypes::samplingMode_syncBurst) { - outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_SWEEPS, "The number of Sweeps exceeds the max for this Configuration.")); + //verify the number of sweeps works with the other sampling settings + if(numSweeps > features.maxSweeps(samplingMode, dataFormat, channels)) + { + outIssues.push_back(ConfigIssue(ConfigIssue::CONFIG_SWEEPS, "The number of Sweeps exceeds the max for this Configuration.")); + } } } } @@ -536,6 +609,9 @@ namespace mscl //write Histogram Options if(isSet(m_histogramOptions)) { eeprom.write_histogramOptions(*m_histogramOptions); } + //write Activity Sense Options + if(isSet(m_activitySense)) { eeprom.write_activitySense(*m_activitySense); } + //write Hardware Gain(s) for(const auto& gain : m_hardwareGains) { @@ -548,6 +624,12 @@ namespace mscl eeprom.write_hardwareOffset(offset.first, offset.second); } + //write Gauge Factor(s) + for(const auto& factor : m_gaugeFactors) + { + eeprom.write_gaugeFactor(factor.first, factor.second); + } + //write Linear Equation(s) for(const auto& eq : m_linearEquations) { @@ -742,6 +824,16 @@ namespace mscl setChannelMapVal(m_hardwareOffsets, mask, offset); } + float WirelessNodeConfig::gaugeFactor(const ChannelMask& mask) const + { + return getChannelMapVal(m_gaugeFactors, mask, "Gauge Factor"); + } + + void WirelessNodeConfig::gaugeFactor(const ChannelMask& mask, float factor) + { + setChannelMapVal(m_gaugeFactors, mask, factor); + } + const LinearEquation& WirelessNodeConfig::linearEquation(const ChannelMask& mask) const { return getChannelMapVal(m_linearEquations, mask, "Linear Equation"); @@ -813,4 +905,15 @@ namespace mscl { m_histogramOptions = histogramOpts; } + + const ActivitySense& WirelessNodeConfig::activitySense() const + { + checkValue(m_activitySense, "Activity Sense"); + return *m_activitySense; + } + + void WirelessNodeConfig::activitySense(const ActivitySense& activitySenseOpts) + { + m_activitySense = activitySenseOpts; + } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/WirelessNodeConfig.h b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/WirelessNodeConfig.h index 8a435c978..8a0af16fc 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Configuration/WirelessNodeConfig.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Configuration/WirelessNodeConfig.h @@ -15,6 +15,7 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #include "mscl/MicroStrain/Wireless/ChannelMask.h" #include "mscl/Exceptions.h" #include "mscl/TimeSpan.h" +#include "ActivitySense.h" #include "ConfigIssue.h" #include "FatigueOptions.h" #include "HistogramOptions.h" @@ -100,6 +101,10 @@ namespace mscl // The to set. boost::optional m_histogramOptions; + //Variable: m_activitySense + // The to set. + boost::optional m_activitySense; + //Variable: m_hardwareGains // The map of to hardware gains to set. std::map m_hardwareGains; @@ -108,6 +113,10 @@ namespace mscl // The map of to hardware offsets to set. std::map m_hardwareOffsets; + //Variable: m_gaugeFactors + // The map of to gauge factors to set. + std::map m_gaugeFactors; + //Variable: m_settlingTimes // The map of to to set. std::map m_settlingTimes; @@ -518,6 +527,20 @@ namespace mscl // Sets the hardware offset for the given in the Config. void hardwareOffset(const ChannelMask& mask, uint16 offset); + //API Function: gaugeFactor + // Gets the gauge factor for the given in the Config, if set. + // + //Parameters: + // mask - The to set the gauge factor for. + // + //Exceptions: + // - The requested value has not been set. + float gaugeFactor(const ChannelMask& mask) const; + + //API Function: gaugeFactor + // Sets the gauge Factor for the given in the Config. + void gaugeFactor(const ChannelMask& mask, float factor); + //API Function: linearEquation // Gets the for the given in the Config, if set. // @@ -606,8 +629,19 @@ namespace mscl // - The requested value has not been set. const HistogramOptions& histogramOptions() const; - //Api Function: histogramOptions + //API Function: histogramOptions // Sets the in the Config. void histogramOptions(const HistogramOptions& histogramOpts); + + //API Function: activitySense + // Gets the currently set in the Config. + // + //Exceptions: + // - The requested value has not been set. + const ActivitySense& activitySense() const; + + //API Function: activitySense + // Sets the in the Config. + void activitySense(const ActivitySense& activitySenseOpts); }; } diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/BaseStationFeatures.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/BaseStationFeatures.cpp index 7cffa6524..9a6ce0bda 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/BaseStationFeatures.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/BaseStationFeatures.cpp @@ -91,6 +91,11 @@ namespace mscl WirelessTypes::TransmitPower maxPower = WirelessTypes::maxTransmitPower(m_baseInfo.regionCode); //add the power levels based on the max power we determined above + if(maxPower >= WirelessTypes::power_20dBm && supportsNewTransmitPowers()) + { + result.push_back(WirelessTypes::power_20dBm); + } + if(maxPower >= WirelessTypes::power_16dBm) { result.push_back(WirelessTypes::power_16dBm); @@ -113,4 +118,18 @@ namespace mscl return result; } + + bool BaseStationFeatures::supportsNewTransmitPowers() const + { + static const Version MIN_NEW_TX_POWER_FW(4, 0); + + return (m_baseInfo.firmwareVersion >= MIN_NEW_TX_POWER_FW); + } + + bool BaseStationFeatures::supportsEepromCommitViaRadioReset() const + { + static const Version MIN_EEPROM_COMMIT_RADIO_FW(4, 0); + + return (m_baseInfo.firmwareVersion >= MIN_EEPROM_COMMIT_RADIO_FW); + } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/BaseStationFeatures.h b/MSCL/source/mscl/MicroStrain/Wireless/Features/BaseStationFeatures.h index 855fcad00..587070b65 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/BaseStationFeatures.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/BaseStationFeatures.h @@ -17,6 +17,7 @@ namespace mscl class BaseStationFeatures { friend class BaseStationEepromHelper; + friend class BaseStation_Impl; public: virtual ~BaseStationFeatures() {}; @@ -104,5 +105,14 @@ namespace mscl //Returns: // A vector of that are supported by this BaseStation. virtual const WirelessTypes::TransmitPowers transmitPowers() const; + + protected: + //Function: supportsNewTransmitPowers + // Checks if the BaseStation supports the new transmit powers (true), or the old ones (false). + virtual bool supportsNewTransmitPowers() const; + + //Function: supportsEepromCommitViaRadioReset + // Checks if eeprom changes can be committed by only cycling the radio, instead of cycling power. + virtual bool supportsEepromCommitViaRadioReset() const; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures.cpp index 1ae2411ce..120b3343a 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures.cpp @@ -25,6 +25,7 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #include "NodeFeatures_sglinkoem.h" #include "NodeFeatures_sglinkoemHermetic.h" #include "NodeFeatures_sglinkoemNoXR.h" +#include "NodeFeatures_sglinkMicro.h" #include "NodeFeatures_sglinkrgd.h" #include "NodeFeatures_shmlink.h" #include "NodeFeatures_shmlink2.h" @@ -92,6 +93,9 @@ namespace mscl case WirelessModels::node_sgLink_oem: return std::unique_ptr(new NodeFeatures_sglinkoem(info)); + case WirelessModels::node_sgLink_micro: + return std::unique_ptr(new NodeFeatures_sglinkMicro(info)); + case WirelessModels::node_sgLink_herm: case WirelessModels::node_sgLink_herm_2600: case WirelessModels::node_sgLink_herm_2700: @@ -108,6 +112,7 @@ namespace mscl return std::unique_ptr(new NodeFeatures_shmlink(info)); case WirelessModels::node_shmLink2: + case WirelessModels::node_shmLink2_cust1: return std::unique_ptr(new NodeFeatures_shmlink2(info)); case WirelessModels::node_tcLink_1ch: @@ -336,6 +341,23 @@ namespace mscl return anyChannelGroupSupports(WirelessTypes::chSetting_hardwareGain); } + bool NodeFeatures::supportsHardwareOffset() const + { + return anyChannelGroupSupports(WirelessTypes::chSetting_hardwareOffset); + } + + bool NodeFeatures::supportsGaugeFactor() const + { + return anyChannelGroupSupports(WirelessTypes::chSetting_gaugeFactor); + } + + bool NodeFeatures::supportsLostBeaconTimeout() const + { + //if the node supports sync sampling, it supports lost beacon timeout + return (supportsSamplingMode(WirelessTypes::samplingMode_sync) || + supportsSamplingMode(WirelessTypes::samplingMode_syncBurst)); + } + bool NodeFeatures::supportsFilterSettlingTime() const { return anyChannelGroupSupports(WirelessTypes::chSetting_filterSettlingTime); @@ -361,7 +383,12 @@ namespace mscl return false; } - bool NodeFeatures::supportsFatigueRawModeConfig() const + bool NodeFeatures::supportsFatigueDebugModeConfig() const + { + return false; + } + + bool NodeFeatures::supportsFatigueModeConfig() const { return false; } @@ -376,16 +403,31 @@ namespace mscl return false; } - bool NodeFeatures::supportsAutoCal() const + bool NodeFeatures::supportsHistogramEnableConfig() const { return false; } - bool NodeFeatures::supportsAutoBalance(uint8 channelNumber) const + bool NodeFeatures::supportsActivitySense() const { return false; } + bool NodeFeatures::supportsAutoCal() const + { + return false; + } + + bool NodeFeatures::supportsLimitedDuration() const + { + return true; + } + + bool NodeFeatures::supportsAutoBalance() const + { + return anyChannelGroupSupports(WirelessTypes::chSetting_autoBalance); + } + bool NodeFeatures::supportsChannel(uint8 channelNumber) const { //try to find the channel number in the vector of channels @@ -463,6 +505,15 @@ namespace mscl return (std::find(supportedPowers.begin(), supportedPowers.end(), power) != supportedPowers.end()); } + bool NodeFeatures::supportsFatigueMode(WirelessTypes::FatigueMode mode) const + { + //get the supported fatigue modes + const WirelessTypes::FatigueModes modes = fatigueModes(); + + //result the result of trying to find the mode in the vector + return (std::find(modes.begin(), modes.end(), mode) != modes.end()); + } + WirelessTypes::WirelessSampleRate NodeFeatures::maxSampleRate(WirelessTypes::SamplingMode samplingMode, const ChannelMask& channels) const { //get all the sample rates supported @@ -513,11 +564,21 @@ namespace mscl uint32 NodeFeatures::minSweeps() const { + if(!supportsLimitedDuration()) + { + return 0; + } + return 100; } uint32 NodeFeatures::maxSweeps(WirelessTypes::SamplingMode samplingMode, WirelessTypes::DataFormat dataFormat, const ChannelMask& channels) const { + if(!supportsLimitedDuration()) + { + return 0; + } + //if this is burst mode if(samplingMode == WirelessTypes::samplingMode_syncBurst) { @@ -533,6 +594,11 @@ namespace mscl uint32 NodeFeatures::maxSweeps(WirelessTypes::DataFormat dataFormat, const ChannelMask& channels) const { + if(!supportsLimitedDuration()) + { + return 0; + } + //get the max number of bytes this node can store to memory uint64 maxBytes = m_nodeInfo.dataStorageSize; @@ -676,6 +742,11 @@ namespace mscl WirelessTypes::TransmitPower maxPower = WirelessTypes::maxTransmitPower(m_nodeInfo.regionCode); //add the power levels based on the max power we determined above + if(maxPower >= WirelessTypes::power_20dBm && supportsNewTransmitPowers()) + { + result.push_back(WirelessTypes::power_20dBm); + } + if(maxPower >= WirelessTypes::power_16dBm) { result.push_back(WirelessTypes::power_16dBm); @@ -705,4 +776,32 @@ namespace mscl WirelessTypes::WirelessSampleRates result; return result; } + + const WirelessTypes::FatigueModes NodeFeatures::fatigueModes() const + { + //empty by default + WirelessTypes::FatigueModes result; + return result; + } + + bool NodeFeatures::supportsNewTransmitPowers() const + { + static const Version MIN_NEW_TX_POWER_FW(10, 0); + + return (m_nodeInfo.firmwareVersion >= MIN_NEW_TX_POWER_FW); + } + + bool NodeFeatures::supportsAutoBalance2() const + { + static const Version MIN_AUTOBALANCE_2_FW(10, 0); + + //if it supports autobalance in general, and has the correct firmware + if(supportsAutoBalance() && + m_nodeInfo.firmwareVersion >= MIN_AUTOBALANCE_2_FW) + { + return true; + } + + return false; + } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures.h b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures.h index 07fd5b652..e514491bd 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures.h @@ -176,6 +176,27 @@ namespace mscl // true if the Node supports Hardware Gain for at least one , false otherwise. bool supportsHardwareGain() const; + //API Function: supportsHardwareOffset + // Checks if the Node supports Hardware Offset for any of its . + // + //Returns: + // true if the Node supports Hardware Offset for at least one , false otherwise. + bool supportsHardwareOffset() const; + + //API Function: supportsGaugeFactor + // Checks if the Node supports Gauge Factor for any of its . + // + //Returns: + // true if the Node support Gauge Factor for at least on , false otherwise. + bool supportsGaugeFactor() const; + + //API Function: supportsLostBeaconTimeout + // Checks if the Node supports the Lost Beacon Timeout option. + // + //Returns: + // true if the Node supports Lost Beacon Timeout, false otherwise. + virtual bool supportsLostBeaconTimeout() const; + //API Function: supportsFilterSettlingTime // Checks if the Node supports Filter Settling Time for any of its . // @@ -211,12 +232,19 @@ namespace mscl // true if the Node supports Poisson's Ratio configuration, false otherwise. virtual bool supportsPoissonsRatioConfig() const; - //API Function: supportsFatigueRawModeConfig - // Checks if the Node supports enabling Raw Mode (part of ) configuration. + //API Function: supportsFatigueDebugModeConfig + // Checks if the Node supports enabling Debug Mode (part of ) configuration. // //Returns: - // true if the Node supports Raw Mode configuration, false otherwise. - virtual bool supportsFatigueRawModeConfig() const; + // true if the Node supports Debug Mode configuration, false otherwise. + virtual bool supportsFatigueDebugModeConfig() const; + + //API Function: supportsFatigueModeConfig + // Checks if the Node supports Fatigue Mode (part of ) configuration. + // + //Returns: + // true if the Node supports Fatigue Mode configuration, false otherwise. + virtual bool supportsFatigueModeConfig() const; //API Function: supportsHistogramConfig // Checks if the Node supports configuration. @@ -232,15 +260,26 @@ namespace mscl // true if the Node supports Histogram transmit rate configuration, false otherwise. virtual bool supportsHistogramRateConfig() const; - //API Function: supportsAutoBalance - // Checks if the Node supports the AutoBalance command for a specified channel. + //API Function: supportsHistogramEnableConfig + // Checks if the Node supports turning Histograms on and off (part of ). // - //Parameters: - // channelNumber - The channel number (ch1 = 1, ch8 = 8) to check if autobalance is supported. + //Returns: + // true if the Node supports turning Histograms on and off, false otherwise. + virtual bool supportsHistogramEnableConfig() const; + + //API Function: supportsActivitySense + // Checks if the Node supports the feature. + // + //Returns: + // true if the Node supports and can be configured for it. + virtual bool supportsActivitySense() const; + + //API Function: supportsAutoBalance + // Checks if the Node supports the Auto Balance command for any of its . // //Returns: - // true if the Node supports autobalance of the specified channel, false otherwise. - virtual bool supportsAutoBalance(uint8 channelNumber) const; + // true if the Node supports Auto Balance for at least 1 , false otherwise. + virtual bool supportsAutoBalance() const; //API Function: supportsAutoCal // Checks if the Node supports the AutoCal commands. @@ -249,6 +288,13 @@ namespace mscl // true if the Node supports an AutoCal command, false otherwise. virtual bool supportsAutoCal() const; + //API Function: supportsLimitedDuration + // Checks if the Node supports setting a limited duration of sampling. + // + //Returns: + // true if the Node supported limited duration, false if the Node only supports unlimited sampling. + virtual bool supportsLimitedDuration() const; + //API Function: supportsChannel // Checks if a specific channel is supported (can be enabled) by this Node. // @@ -320,6 +366,16 @@ namespace mscl // true if the transmit power is supported, false otherwise. bool supportsTransmitPower(WirelessTypes::TransmitPower power) const; + //API Function: supportsFatigueMode + // Checks if a is supported by this Node. + // + //Parameters: + // mode - The to check if supported. + // + //Returns: + // true if the fatigue mode is supported, false otherwise. + bool supportsFatigueMode(WirelessTypes::FatigueMode mode) const; + //API Function: maxSampleRate // Gets the maximum value that is supported by this Node with the given and . // @@ -530,5 +586,21 @@ namespace mscl //Returns: // A vector of s representing the Histogram Transmit Rates that are supported by this Node. virtual const WirelessTypes::WirelessSampleRates histogramTransmitRates() const; + + //API Function: fatigueModes + // Gets a list of the s that are supported by this Node. + // + //Returns: + // A vector of supported by the Node. + virtual const WirelessTypes::FatigueModes fatigueModes() const; + + protected: + //Function: supportsNewTransmitPowers + // Checks if the Node supports the new transmit powers (true), or the old ones (false). + virtual bool supportsNewTransmitPowers() const; + + //Function: supportsAutoBalance2 + // Checks if the Node supports the AutoBalance (Version 2) command. + virtual bool supportsAutoBalance2() const; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_envlinkPro.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_envlinkPro.cpp index 059c8256f..13cb3208b 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_envlinkPro.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_envlinkPro.cpp @@ -48,7 +48,7 @@ namespace mscl m_channels.emplace_back(5, WirelessChannel::channel_5, WirelessTypes::chType_voltage); //voltage m_channels.emplace_back(6, WirelessChannel::channel_6, WirelessTypes::chType_voltage); //voltage m_channels.emplace_back(7, WirelessChannel::channel_7, WirelessTypes::chType_temperature); //internal temp - m_channels.emplace_back(8, WirelessChannel::channel_8, WirelessTypes::chType_rh); //% RH + m_channels.emplace_back(8, WirelessChannel::channel_8, WirelessTypes::chType_rh); //% RH } const WirelessTypes::SamplingModes NodeFeatures_envlinkPro::samplingModes() const diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_mvpervlink.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_mvpervlink.cpp index 6a6c05524..5da2aa4ea 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_mvpervlink.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_mvpervlink.cpp @@ -18,11 +18,17 @@ namespace mscl m_channelGroups.emplace_back(DIFFERENTIAL_CHS, "Differential Channels", ChannelGroup::SettingsMap{ {WirelessTypes::chSetting_hardwareGain, NodeEepromMap::HW_GAIN_1}, - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_1}} ); //Channels - m_channels.emplace_back(1, WirelessChannel::channel_1, WirelessTypes::chType_none); + m_channels.emplace_back(1, WirelessChannel::channel_1, WirelessTypes::chType_fullDifferential); + } + + bool NodeFeatures_mvpervlink::supportsLimitedDuration() const + { + return false; } const WirelessTypes::DataCollectionMethods NodeFeatures_mvpervlink::dataCollectionMethods() const diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_mvpervlink.h b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_mvpervlink.h index a8a9914e0..640fb503c 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_mvpervlink.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_mvpervlink.h @@ -23,6 +23,8 @@ namespace mscl // Creates a NodeFeatures_mvpervlink object. NodeFeatures_mvpervlink(const NodeInfo& info); + virtual bool supportsLimitedDuration() const; + virtual const WirelessTypes::DataCollectionMethods dataCollectionMethods() const final; virtual const WirelessTypes::DataFormats dataFormats() const final; diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_rtdlink.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_rtdlink.cpp index 41eaa336f..e7afe60c6 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_rtdlink.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_rtdlink.cpp @@ -32,7 +32,7 @@ namespace mscl m_channels.emplace_back(1, WirelessChannel::channel_1, WirelessTypes::chType_diffTemperature); //4-wire m_channels.emplace_back(2, WirelessChannel::channel_2, WirelessTypes::chType_diffTemperature); //2-wire m_channels.emplace_back(7, WirelessChannel::channel_7, WirelessTypes::chType_temperature); //internal temp - m_channels.emplace_back(8, WirelessChannel::channel_8, WirelessTypes::chType_rh); //% RH + m_channels.emplace_back(8, WirelessChannel::channel_8, WirelessTypes::chType_rh); //% RH } const WirelessTypes::SamplingModes NodeFeatures_rtdlink::samplingModes() const diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglink.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglink.cpp index 31d725e5f..8eb5d9b47 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglink.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglink.cpp @@ -18,7 +18,8 @@ namespace mscl m_channelGroups.emplace_back(DIFFERENTIAL_CHS, "Differential Channels", ChannelGroup::SettingsMap{ {WirelessTypes::chSetting_hardwareGain, NodeEepromMap::HW_GAIN_1}, - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_1}} ); addCalCoeffChannelGroup(1, NodeEepromMap::CH_ACTION_SLOPE_1, NodeEepromMap::CH_ACTION_ID_1); @@ -30,9 +31,4 @@ namespace mscl m_channels.emplace_back(3, WirelessChannel::channel_3, WirelessTypes::chType_temperature); //internal temp m_channels.emplace_back(4, WirelessChannel::channel_4, WirelessTypes::chType_voltage); //voltage } - - bool NodeFeatures_sglink::supportsAutoBalance(uint8 channelNumber) const - { - return anyChannelGroupSupports(WirelessTypes::chSetting_hardwareOffset, channelNumber); - } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglink.h b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglink.h index 3d2b3c840..0f52802aa 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglink.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglink.h @@ -22,7 +22,5 @@ namespace mscl //Constructor: NodeFeatures_sglink // Creates a NodeFeatures_sglink object. NodeFeatures_sglink(const NodeInfo& info); - - virtual bool supportsAutoBalance(uint8 channelNumber) const final; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkMicro.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkMicro.cpp new file mode 100644 index 000000000..fdded9f4b --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkMicro.cpp @@ -0,0 +1,70 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "NodeFeatures_sglinkMicro.h" +#include "mscl/MicroStrain/Wireless/Configuration/NodeEepromMap.h" +#include "mscl/Utils.h" + +namespace mscl +{ + NodeFeatures_sglinkMicro::NodeFeatures_sglinkMicro(const NodeInfo& info): + NodeFeatures(info) + { + addCalCoeffChannelGroup(1, NodeEepromMap::CH_ACTION_SLOPE_1, NodeEepromMap::CH_ACTION_ID_1); + addCalCoeffChannelGroup(3, NodeEepromMap::CH_ACTION_SLOPE_3, NodeEepromMap::CH_ACTION_ID_3); + + static const ChannelMask DIFFERENTIAL_CHS(BOOST_BINARY(00000001)); //ch1 + + m_channelGroups.emplace_back(DIFFERENTIAL_CHS, "Differential Channels", + ChannelGroup::SettingsMap{ + {WirelessTypes::chSetting_hardwareGain, NodeEepromMap::HW_GAIN_1}, + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_1}} + ); + + //Channels + m_channels.emplace_back(1, WirelessChannel::channel_1, WirelessTypes::chType_fullDifferential); //full diff + m_channels.emplace_back(3, WirelessChannel::channel_3, WirelessTypes::chType_temperature); //temperature + } + + const WirelessTypes::DataCollectionMethods NodeFeatures_sglinkMicro::dataCollectionMethods() const + { + WirelessTypes::DataCollectionMethods result; + + result.push_back(WirelessTypes::collectionMethod_transmitOnly); + + //no log only + //no log and transmit + + return result; + } + + const WirelessTypes::DataFormats NodeFeatures_sglinkMicro::dataFormats() const + { + //build and return the data formats that are supported (all for generic) + WirelessTypes::DataFormats result; + + result.push_back(WirelessTypes::dataFormat_4byte_float); + + //no uint16 + + return result; + } + + const WirelessTypes::SamplingModes NodeFeatures_sglinkMicro::samplingModes() const + { + //build and return the sampling modes that are supported (all for generic) + WirelessTypes::SamplingModes result; + + result.push_back(WirelessTypes::samplingMode_sync); + result.push_back(WirelessTypes::samplingMode_nonSync); + result.push_back(WirelessTypes::samplingMode_armedDatalog); + + //no burst + + return result; + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkMicro.h b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkMicro.h new file mode 100644 index 000000000..70914d023 --- /dev/null +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkMicro.h @@ -0,0 +1,32 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include "NodeFeatures.h" + +namespace mscl +{ + //Class: NodeFeatures_sglinkMicro + // Contains information on features for the SG-Link-Micro node. Inherits from . + class NodeFeatures_sglinkMicro: public NodeFeatures + { + private: + NodeFeatures_sglinkMicro(); //disabled default constructor + + public: + virtual ~NodeFeatures_sglinkMicro() {}; + + //Constructor: NodeFeatures_sglinkMicro + // Creates a NodeFeatures_sglinkMicro object. + NodeFeatures_sglinkMicro(const NodeInfo& info); + + virtual const WirelessTypes::DataCollectionMethods dataCollectionMethods() const final; + + virtual const WirelessTypes::DataFormats dataFormats() const; + + virtual const WirelessTypes::SamplingModes samplingModes() const; + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoem.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoem.cpp index 1485e9925..3dba12227 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoem.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoem.cpp @@ -22,7 +22,8 @@ namespace mscl m_channelGroups.emplace_back(DIFFERENTIAL_CHS, "Differential Channels", ChannelGroup::SettingsMap{ {WirelessTypes::chSetting_hardwareGain, NodeEepromMap::HW_GAIN_1}, - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_1}} ); //Channels @@ -30,9 +31,4 @@ namespace mscl m_channels.emplace_back(3, WirelessChannel::channel_3, WirelessTypes::chType_temperature); //temperature m_channels.emplace_back(4, WirelessChannel::channel_4, WirelessTypes::chType_voltage); //voltage } - - bool NodeFeatures_sglinkoem::supportsAutoBalance(uint8 channelNumber) const - { - return anyChannelGroupSupports(WirelessTypes::chSetting_hardwareOffset, channelNumber); - } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoem.h b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoem.h index 4ea30f84d..8d4df7cb5 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoem.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoem.h @@ -22,7 +22,5 @@ namespace mscl //Constructor: NodeFeatures_sglinkoem // Creates a NodeFeatures_sglinkoem object. NodeFeatures_sglinkoem(const NodeInfo& info); - - virtual bool supportsAutoBalance(uint8 channelNumber) const final; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemHermetic.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemHermetic.cpp index ba5447448..790b8e961 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemHermetic.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemHermetic.cpp @@ -23,7 +23,8 @@ namespace mscl m_channelGroups.emplace_back(DIFFERENTIAL_CHS, "Differential Channels", ChannelGroup::SettingsMap{ {WirelessTypes::chSetting_hardwareGain, NodeEepromMap::HW_GAIN_1}, - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_1}} ); //Channels @@ -32,9 +33,4 @@ namespace mscl m_channels.emplace_back(3, WirelessChannel::channel_3, WirelessTypes::chType_temperature); //temp m_channels.emplace_back(4, WirelessChannel::channel_4, WirelessTypes::chType_voltage); //voltage } - - bool NodeFeatures_sglinkoemHermetic::supportsAutoBalance(uint8 channelNumber) const - { - return anyChannelGroupSupports(WirelessTypes::chSetting_hardwareOffset, channelNumber); - } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemHermetic.h b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemHermetic.h index 5f13e2f67..18011d620 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemHermetic.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemHermetic.h @@ -22,7 +22,5 @@ namespace mscl //Constructor: NodeFeatures_sglinkoemHermetic // Creates a NodeFeatures_sglinkoemHermetic object. NodeFeatures_sglinkoemHermetic(const NodeInfo& info); - - virtual bool supportsAutoBalance(uint8 channelNumber) const final; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemNoXR.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemNoXR.cpp index f75e492d9..06a7a769b 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemNoXR.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemNoXR.cpp @@ -22,7 +22,8 @@ namespace mscl m_channelGroups.emplace_back(DIFFERENTIAL_CHS, "Differential Channels", ChannelGroup::SettingsMap{ {WirelessTypes::chSetting_hardwareGain, NodeEepromMap::HW_GAIN_1}, - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_1}} ); //Channels @@ -30,9 +31,4 @@ namespace mscl m_channels.emplace_back(3, WirelessChannel::channel_3, WirelessTypes::chType_temperature); //temp m_channels.emplace_back(4, WirelessChannel::channel_4, WirelessTypes::chType_voltage); //voltage } - - bool NodeFeatures_sglinkoemNoXR::supportsAutoBalance(uint8 channelNumber) const - { - return anyChannelGroupSupports(WirelessTypes::chSetting_hardwareOffset, channelNumber); - } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemNoXR.h b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemNoXR.h index 3184b0fd0..4e7ffa9e9 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemNoXR.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkoemNoXR.h @@ -22,7 +22,5 @@ namespace mscl //Constructor: NodeFeatures_sglinkoemNoXR // Creates a NodeFeatures_sglinkoemNoXR object. NodeFeatures_sglinkoemNoXR(const NodeInfo& info); - - virtual bool supportsAutoBalance(uint8 channelNumber) const final; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkrgd.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkrgd.cpp index af5b068cb..95b34250c 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkrgd.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkrgd.cpp @@ -26,22 +26,26 @@ namespace mscl m_channelGroups.emplace_back(DIFF_CH1, "Differential Channel 1", ChannelGroup::SettingsMap{ - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_1}} ); m_channelGroups.emplace_back(DIFF_CH2, "Differential Channel 2", ChannelGroup::SettingsMap{ - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_2}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_2}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_2}} ); m_channelGroups.emplace_back(DIFF_CH3, "Differential Channel 3", ChannelGroup::SettingsMap{ - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_3}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_3}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_3}} ); m_channelGroups.emplace_back(DIFF_CH4, "Differential Channel 4", ChannelGroup::SettingsMap{ - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_4}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_4}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_4}} ); addCalCoeffChannelGroup(1, NodeEepromMap::CH_ACTION_SLOPE_1, NodeEepromMap::CH_ACTION_ID_1); @@ -63,9 +67,4 @@ namespace mscl m_channels.emplace_back(7, WirelessChannel::channel_7, WirelessTypes::chType_acceleration); //accel z m_channels.emplace_back(8, WirelessChannel::channel_8, WirelessTypes::chType_temperature); //temp } - - bool NodeFeatures_sglinkrgd::supportsAutoBalance(uint8 channelNumber) const - { - return anyChannelGroupSupports(WirelessTypes::chSetting_hardwareOffset, channelNumber); - } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkrgd.h b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkrgd.h index a98b5c22c..249909a3a 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkrgd.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_sglinkrgd.h @@ -22,7 +22,5 @@ namespace mscl //Constructor: NodeFeatures_sglinkrgd // Creates a NodeFeatures_sglinkrgd object. NodeFeatures_sglinkrgd(const NodeInfo& info); - - virtual bool supportsAutoBalance(uint8 channelNumber) const final; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink.cpp index 283a6f25b..66ffb0d50 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink.cpp @@ -33,17 +33,20 @@ namespace mscl m_channelGroups.emplace_back(DIFF_CH1, "Differential Channel 1", ChannelGroup::SettingsMap{ - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_1}} ); m_channelGroups.emplace_back(DIFF_CH2, "Differential Channel 2", ChannelGroup::SettingsMap{ - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_2}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_2}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_2}} ); m_channelGroups.emplace_back(DIFF_CH3, "Differential Channel 3", ChannelGroup::SettingsMap{ - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_3}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_3}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_3}} ); //Channels @@ -56,11 +59,6 @@ namespace mscl m_channels.emplace_back(8, WirelessChannel::channel_8, WirelessTypes::chType_temperature); //temp } - bool NodeFeatures_shmlink::supportsAutoBalance(uint8 channelNumber) const - { - return anyChannelGroupSupports(WirelessTypes::chSetting_hardwareOffset, channelNumber); - } - bool NodeFeatures_shmlink::supportsFatigueConfig() const { return true; @@ -76,7 +74,7 @@ namespace mscl return false; //this version of the shm-link has a hard-coded Poisson's Ratio } - bool NodeFeatures_shmlink::supportsFatigueRawModeConfig() const + bool NodeFeatures_shmlink::supportsFatigueDebugModeConfig() const { return false; //this version of the shm-link does not allow eeprom configuration of raw mode } @@ -91,6 +89,11 @@ namespace mscl return false; //this version of the shm-link has a hard-coded Histogram Rate } + bool NodeFeatures_shmlink::supportsHistogramEnableConfig() const + { + return false; //this version of the shm-link does not allow turning the histogram on and off + } + uint8 NodeFeatures_shmlink::numDamageAngles() const { return 3; @@ -109,4 +112,13 @@ namespace mscl return HistogramRates; } + + const WirelessTypes::FatigueModes NodeFeatures_shmlink::fatigueModes() const + { + static const WirelessTypes::FatigueModes modes = { + {WirelessTypes::fatigueMode_angleStrain} + }; + + return modes; + } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink.h b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink.h index 87b5d67ba..076261d7d 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink.h @@ -24,24 +24,26 @@ namespace mscl NodeFeatures_shmlink(const NodeInfo& info); public: - virtual bool supportsAutoBalance(uint8 channelNumber) const final; - virtual bool supportsFatigueConfig() const final; virtual bool supportsYoungsModConfig() const final; virtual bool supportsPoissonsRatioConfig() const final; - virtual bool supportsFatigueRawModeConfig() const final; + virtual bool supportsFatigueDebugModeConfig() const final; virtual bool supportsHistogramConfig() const final; virtual bool supportsHistogramRateConfig() const final; + virtual bool supportsHistogramEnableConfig() const final; + virtual uint8 numDamageAngles() const final; virtual uint8 numSnCurveSegments() const final; virtual const WirelessTypes::WirelessSampleRates histogramTransmitRates() const final; + + virtual const WirelessTypes::FatigueModes fatigueModes() const final; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink2.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink2.cpp index d65330bf8..911f59b2b 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink2.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink2.cpp @@ -13,13 +13,24 @@ namespace mscl NodeFeatures_shmlink2::NodeFeatures_shmlink2(const NodeInfo& info): NodeFeatures(info) { - addCalCoeffChannelGroup(1, NodeEepromMap::CH_ACTION_SLOPE_1, NodeEepromMap::CH_ACTION_ID_1); - addCalCoeffChannelGroup(2, NodeEepromMap::CH_ACTION_SLOPE_2, NodeEepromMap::CH_ACTION_ID_2); - addCalCoeffChannelGroup(3, NodeEepromMap::CH_ACTION_SLOPE_3, NodeEepromMap::CH_ACTION_ID_3); - addCalCoeffChannelGroup(5, NodeEepromMap::CH_ACTION_SLOPE_5, NodeEepromMap::CH_ACTION_ID_5); - addCalCoeffChannelGroup(6, NodeEepromMap::CH_ACTION_SLOPE_6, NodeEepromMap::CH_ACTION_ID_6); - addCalCoeffChannelGroup(7, NodeEepromMap::CH_ACTION_SLOPE_7, NodeEepromMap::CH_ACTION_ID_7); - addCalCoeffChannelGroup(8, NodeEepromMap::CH_ACTION_SLOPE_8, NodeEepromMap::CH_ACTION_ID_8); + static const ChannelMask DIFF_CH1(BOOST_BINARY(00000001)); //ch1 + static const ChannelMask DIFF_CH2(BOOST_BINARY(00000010)); //ch2 + static const ChannelMask DIFF_CH3(BOOST_BINARY(00000100)); //ch3 + + m_channelGroups.emplace_back(DIFF_CH1, "Differential Channel 1", + ChannelGroup::SettingsMap{ + {WirelessTypes::chSetting_gaugeFactor, NodeEepromMap::GAUGE_FACTOR_1}} + ); + + m_channelGroups.emplace_back(DIFF_CH2, "Differential Channel 2", + ChannelGroup::SettingsMap{ + {WirelessTypes::chSetting_gaugeFactor, NodeEepromMap::GAUGE_FACTOR_2}} + ); + + m_channelGroups.emplace_back(DIFF_CH3, "Differential Channel 3", + ChannelGroup::SettingsMap{ + {WirelessTypes::chSetting_gaugeFactor, NodeEepromMap::GAUGE_FACTOR_3}} + ); //Channels m_channels.emplace_back(1, WirelessChannel::channel_1, WirelessTypes::chType_fullDifferential); //full diff @@ -57,6 +68,11 @@ namespace mscl return result; } + bool NodeFeatures_shmlink2::supportsLimitedDuration() const + { + return false; + } + bool NodeFeatures_shmlink2::supportsFatigueConfig() const { return true; @@ -72,7 +88,12 @@ namespace mscl return true; } - bool NodeFeatures_shmlink2::supportsFatigueRawModeConfig() const + bool NodeFeatures_shmlink2::supportsFatigueDebugModeConfig() const + { + return true; + } + + bool NodeFeatures_shmlink2::supportsFatigueModeConfig() const { return true; } @@ -87,6 +108,16 @@ namespace mscl return true; } + bool NodeFeatures_shmlink2::supportsHistogramEnableConfig() const + { + return true; + } + + bool NodeFeatures_shmlink2::supportsActivitySense() const + { + return true; + } + bool NodeFeatures_shmlink2::supportsAutoCal() const { return true; @@ -119,4 +150,15 @@ namespace mscl return HistogramRates; } + + const WirelessTypes::FatigueModes NodeFeatures_shmlink2::fatigueModes() const + { + static const WirelessTypes::FatigueModes modes = { + {WirelessTypes::fatigueMode_angleStrain}, + {WirelessTypes::fatigueMode_distributedAngle}, + {WirelessTypes::fatigueMode_rawGaugeStrain} + }; + + return modes; + } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink2.h b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink2.h index 7e4d5c2f0..c3cd08e67 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink2.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_shmlink2.h @@ -30,18 +30,26 @@ namespace mscl virtual const WirelessTypes::SamplingModes samplingModes() const final; + virtual bool supportsLimitedDuration() const; + virtual bool supportsFatigueConfig() const final; virtual bool supportsYoungsModConfig() const final; virtual bool supportsPoissonsRatioConfig() const final; - virtual bool supportsFatigueRawModeConfig() const final; + virtual bool supportsFatigueDebugModeConfig() const final; + + virtual bool supportsFatigueModeConfig() const final; virtual bool supportsHistogramConfig() const final; virtual bool supportsHistogramRateConfig() const final; + virtual bool supportsHistogramEnableConfig() const; + + virtual bool supportsActivitySense() const final; + virtual bool supportsAutoCal() const; virtual uint8 numDamageAngles() const final; @@ -49,5 +57,7 @@ namespace mscl virtual uint8 numSnCurveSegments() const final; virtual const WirelessTypes::WirelessSampleRates histogramTransmitRates() const final; + + virtual const WirelessTypes::FatigueModes fatigueModes() const final; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_tclink1ch.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_tclink1ch.cpp index 29d405eb8..807fa3e7b 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_tclink1ch.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_tclink1ch.cpp @@ -31,7 +31,7 @@ namespace mscl //Channels m_channels.emplace_back(1, WirelessChannel::channel_1, WirelessTypes::chType_diffTemperature); //temp (thermocouple) m_channels.emplace_back(7, WirelessChannel::channel_7, WirelessTypes::chType_temperature); //cjc temp - m_channels.emplace_back(8, WirelessChannel::channel_8, WirelessTypes::chType_rh); //% RH + m_channels.emplace_back(8, WirelessChannel::channel_8, WirelessTypes::chType_rh); //% RH } const WirelessTypes::SamplingModes NodeFeatures_tclink1ch::samplingModes() const diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_tclink3ch.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_tclink3ch.cpp index 37bfabdac..3594cea82 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_tclink3ch.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_tclink3ch.cpp @@ -35,7 +35,7 @@ namespace mscl m_channels.emplace_back(2, WirelessChannel::channel_2, WirelessTypes::chType_diffTemperature); //temp (thermocouple) m_channels.emplace_back(3, WirelessChannel::channel_3, WirelessTypes::chType_diffTemperature); //temp (thermocouple) m_channels.emplace_back(7, WirelessChannel::channel_7, WirelessTypes::chType_temperature); //CJC - m_channels.emplace_back(8, WirelessChannel::channel_8, WirelessTypes::chType_rh); //% RH + m_channels.emplace_back(8, WirelessChannel::channel_8, WirelessTypes::chType_rh); //% RH } const WirelessTypes::SamplingModes NodeFeatures_tclink3ch::samplingModes() const diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink.cpp index 823067cd8..de42b684b 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink.cpp @@ -34,25 +34,29 @@ namespace mscl m_channelGroups.emplace_back(DIFFERENTIAL_CH1, "Differential Channel 1", ChannelGroup::SettingsMap{ {WirelessTypes::chSetting_hardwareGain, NodeEepromMap::HW_GAIN_1}, - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_1}} ); m_channelGroups.emplace_back(DIFFERENTIAL_CH2, "Differential Channel 2", ChannelGroup::SettingsMap{ {WirelessTypes::chSetting_hardwareGain, NodeEepromMap::HW_GAIN_2}, - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_2}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_2}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_2}} ); m_channelGroups.emplace_back(DIFFERENTIAL_CH3, "Differential Channel 3", ChannelGroup::SettingsMap{ {WirelessTypes::chSetting_hardwareGain, NodeEepromMap::HW_GAIN_3}, - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_3}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_3}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_3}} ); m_channelGroups.emplace_back(DIFFERENTIAL_CH4, "Differential Channel 4", ChannelGroup::SettingsMap{ {WirelessTypes::chSetting_hardwareGain, NodeEepromMap::HW_GAIN_4}, - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_4}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_4}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_4}} ); addCalCoeffChannelGroup(1, NodeEepromMap::CH_ACTION_SLOPE_1, NodeEepromMap::CH_ACTION_ID_1); @@ -136,9 +140,4 @@ namespace mscl return NodeFeatures::maxSampleRate(samplingMode, channels); } } - - bool NodeFeatures_vlink::supportsAutoBalance(uint8 channelNumber) const - { - return anyChannelGroupSupports(WirelessTypes::chSetting_hardwareOffset, channelNumber); - } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink.h b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink.h index 468233ead..20ffe20af 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink.h @@ -31,7 +31,5 @@ namespace mscl //Function: maxSampleRate // Gets the maximum value that is supported by this Node with the given and . virtual WirelessTypes::WirelessSampleRate maxSampleRate(WirelessTypes::SamplingMode samplingMode, const ChannelMask& channels) const override; - - virtual bool supportsAutoBalance(uint8 channelNumber) const final; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink_legacy.cpp b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink_legacy.cpp index 9bb2e570d..cc63a1807 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink_legacy.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink_legacy.cpp @@ -45,22 +45,26 @@ namespace mscl m_channelGroups.emplace_back(DIFF_CH1, "Differential Channel 1", ChannelGroup::SettingsMap{ - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_1}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_1}} ); m_channelGroups.emplace_back(DIFF_CH2, "Differential Channel 2", ChannelGroup::SettingsMap{ - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_2}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_2}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_2}} ); m_channelGroups.emplace_back(DIFF_CH3, "Differential Channel 3", ChannelGroup::SettingsMap{ - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_3}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_3}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_3}} ); m_channelGroups.emplace_back(DIFF_CH4, "Differential Channel 4", ChannelGroup::SettingsMap{ - {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_4}} + {WirelessTypes::chSetting_hardwareOffset, NodeEepromMap::HW_OFFSET_4}, + {WirelessTypes::chSetting_autoBalance, NodeEepromMap::HW_OFFSET_4}} ); addCalCoeffChannelGroup(1, NodeEepromMap::CH_ACTION_SLOPE_1, NodeEepromMap::CH_ACTION_ID_1); @@ -92,9 +96,4 @@ namespace mscl throw Error("Invalid SamplingMode"); } } - - bool NodeFeatures_vlink_legacy::supportsAutoBalance(uint8 channelNumber) const - { - return anyChannelGroupSupports(WirelessTypes::chSetting_hardwareOffset, channelNumber); - } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink_legacy.h b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink_legacy.h index 85a007289..3ac0201e6 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink_legacy.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/Features/NodeFeatures_vlink_legacy.h @@ -27,7 +27,5 @@ namespace mscl //Function: sampleRates // Gets a list of the s that are supported by this Node for the given sampling mode. virtual const WirelessTypes::WirelessSampleRates sampleRates(WirelessTypes::SamplingMode samplingMode) const override; - - virtual bool supportsAutoBalance(uint8 channelNumber) const final; }; } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/SyncSamplingFormulas.cpp b/MSCL/source/mscl/MicroStrain/Wireless/SyncSamplingFormulas.cpp index 149c1707d..346f9b765 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/SyncSamplingFormulas.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/SyncSamplingFormulas.cpp @@ -132,7 +132,7 @@ namespace SyncSamplingFormulas //if the sample rate is 16hz or slower, or the 32hz or faster and a tclink1ch or rtdlink, or the model is SHM-Link if( (sampleRate <= SampleRate::Hertz(16)) || (sampleRate >= SampleRate::Hertz(32) && (nodeModel == WirelessModels::node_tcLink_1ch || nodeModel == WirelessModels::node_rtdLink)) || - (nodeModel == WirelessModels::node_shmLink || nodeModel == WirelessModels::node_shmLink2) + (nodeModel == WirelessModels::node_shmLink || nodeModel == WirelessModels::node_shmLink2 || nodeModel == WirelessModels::node_shmLink2_cust1) ) { return true; diff --git a/MSCL/source/mscl/MicroStrain/Wireless/SyncSamplingNetwork.cpp b/MSCL/source/mscl/MicroStrain/Wireless/SyncSamplingNetwork.cpp index 642d3e12e..13a5374e0 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/SyncSamplingNetwork.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/SyncSamplingNetwork.cpp @@ -1168,6 +1168,7 @@ namespace mscl case WirelessModels::node_shmLink: case WirelessModels::node_shmLink2: + case WirelessModels::node_shmLink2_cust1: case WirelessModels::node_sgLink_herm: case WirelessModels::node_sgLink_herm_2600: case WirelessModels::node_sgLink_herm_2700: diff --git a/MSCL/source/mscl/MicroStrain/Wireless/WirelessChannel.h b/MSCL/source/mscl/MicroStrain/Wireless/WirelessChannel.h index 3e3b756b7..04719bfd1 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/WirelessChannel.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/WirelessChannel.h @@ -255,8 +255,6 @@ namespace mscl WirelessChannel(uint8 chNumber, WirelessChannel::ChannelId id, WirelessTypes::ChannelType type); private: - - //Variable: m_chNumber // The channel number (ch1 = 1) of the channel. uint8 m_chNumber; diff --git a/MSCL/source/mscl/MicroStrain/Wireless/WirelessModels.h b/MSCL/source/mscl/MicroStrain/Wireless/WirelessModels.h index 3e726d57b..67fd6b352 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/WirelessModels.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/WirelessModels.h @@ -30,10 +30,12 @@ namespace mscl //node_gLink_rgd_10g - 63056010 - G-Link-RGD 10G //node_dvrtLink - 63181000 - DVRT-Link //node_shmLink - 63086000 - SHM-Link - //node_shmLink2 - 63089999 - SHM-Link 2 + //node_shmLink2 - 63290000 - SHM-Link 2 + //node_shmLink2_cust1 - 63290100 - SHM-Link 2 - Custom 1 //node_sgLink - 63083000 - SG-Link //node_sgLink_oem_S - 63081000 - SG-Link 0EM -S (non-xr) //node_sgLink_oem - 63084000 - SG-Link OEM + //node_sgLink_micro - 63084100 - SG-Link Micro //node_sgLink_rgd - 63085000 - SG-Link RGD //node_sgLink_herm - 65010000 - SG-Link-Hermetic (Generic) //node_sgLink_herm_2600 - 65011110 - SG-Link-Hermetic 2600 belt assembly @@ -57,7 +59,7 @@ namespace mscl //node_wattLink_3D480 - 63234200 - Watt-Link 3D480 //node_wattLink_3D400 - 63233200 - Watt-Link 3D400 //node_wattLink_3D240 - 63232200 - Watt-Link 3D240 - //node_mvPerVLink - 63230200 - mV/V-Link + //node_mvPerVLink - 63250200 - mV/V-Link //node_envLink_pro - 60000001 - ENV-Link-Pro //node_sgLink_8ch - 60000002 - SG-Link-8CH //========================================================================= @@ -75,9 +77,11 @@ namespace mscl node_dvrtLink = 63181000, //DVRT-Link node_shmLink = 63086000, //SHM-Link node_shmLink2 = 63290000, //SHM-Link 2 + node_shmLink2_cust1 = 63290100, //SHM-Link 2 - Custom 1 node_sgLink = 63083000, //SG-Link node_sgLink_oem_S = 63081000, //SG-Link 0EM -S (non-xr) node_sgLink_oem = 63084000, //SG-Link OEM + node_sgLink_micro = 63084100, //SG-Link Micro node_sgLink_rgd = 63085000, //SG-Link RGD node_sgLink_herm = 65010000, //SG-Link-Hermetic node_sgLink_herm_2600 = 65011110, //SG-Link-Hermetic 2600 belt assembly @@ -101,7 +105,7 @@ namespace mscl node_wattLink_3D480 = 63234200, //Watt-Link 3D480 node_wattLink_3D400 = 63233200, //Watt-Link 3D400 node_wattLink_3D240 = 63232200, //Watt-Link 3D240 - node_mvPerVLink = 63230200, //mV/V-Link + node_mvPerVLink = 63250200, //mV/V-Link //TODO: the following nodes do not currently have 6XXX level model numbers (NODES NEED TO BE UPDATED!) node_envLink_pro = 60000001, diff --git a/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode.cpp b/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode.cpp index 865be3dc7..3b0ef9170 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode.cpp @@ -16,8 +16,8 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. namespace mscl { - WirelessNode::WirelessNode(uint16 nodeAddress, const BaseStation& basestation, WirelessTypes::Frequency nodeFrequency): //nodeFrequency=WirelessTypes::freq_unknown - m_impl(std::make_shared(nodeAddress, basestation, nodeFrequency)) + WirelessNode::WirelessNode(uint16 nodeAddress, const BaseStation& basestation): + m_impl(std::make_shared(nodeAddress, basestation)) { } @@ -101,6 +101,11 @@ namespace mscl return m_impl->frequency(); } + bool WirelessNode::quickPing() + { + return m_impl->quickPing(); + } + PingResponse WirelessNode::ping() { return m_impl->ping(); @@ -146,9 +151,9 @@ namespace mscl m_impl->clearHistogram(); } - void WirelessNode::autoBalance(uint8 channelNumber, WirelessTypes::AutoBalanceOption option) + AutoBalanceResult WirelessNode::autoBalance(const ChannelMask& mask, float targetPercent) { - m_impl->autoBalance(channelNumber, option); + return m_impl->autoBalance(mask, targetPercent); } AutoCalResult_shmLink WirelessNode::autoCal_shmLink() @@ -201,6 +206,11 @@ namespace mscl return m_impl->dataStorageSize(); } + WirelessTypes::RegionCode WirelessNode::regionCode() const + { + return m_impl->regionCode(); + } + bool WirelessNode::verifyConfig(const WirelessNodeConfig& config, ConfigIssues& outIssues) const { return m_impl->verifyConfig(config, outIssues); @@ -291,6 +301,11 @@ namespace mscl return m_impl->getHardwareOffset(mask); } + float WirelessNode::getGaugeFactor(const ChannelMask& mask) const + { + return m_impl->getGaugeFactor(mask); + } + LinearEquation WirelessNode::getLinearEquation(const ChannelMask& mask) const { return m_impl->getLinearEquation(mask); @@ -325,4 +340,9 @@ namespace mscl { return m_impl->getHistogramOptions(); } + + ActivitySense WirelessNode::getActivitySense() const + { + return m_impl->getActivitySense(); + } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode.h b/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode.h index e25f84ee2..99a0d5c49 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode.h @@ -6,8 +6,9 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. //PUBLIC_HEADER #pragma once -#include "Commands/AutoCal.h" +#include "Commands/AutoCalResult.h" #include "Commands/LongPing.h" +#include "Configuration/ActivitySense.h" #include "Configuration/ConfigIssue.h" #include "Configuration/FatigueOptions.h" #include "Configuration/HistogramOptions.h" @@ -44,8 +45,7 @@ namespace mscl //Parameters: // nodeAddress - the node address of the node // base - the node's parent Base Station - // nodeFrequency - the that this node is believed to be on. This parameter is optional. If not used, it will be believed to be on the same frequency as the basestation parameter. - WirelessNode(uint16 nodeAddress, const BaseStation& basestation, WirelessTypes::Frequency nodeFrequency = WirelessTypes::freq_unknown); + WirelessNode(uint16 nodeAddress, const BaseStation& basestation); //Destructor: ~WirelessNode // Destroys a WirelessNode object @@ -260,11 +260,35 @@ namespace mscl // - : A connection error has occurred with the parent BaseStation. uint64 dataStorageSize() const; + //API Function: regionCode + // Gets the region code currently set on the Node. + // + //Exceptions: + // - : Attempted to read an unsupported option. The device firmware is not compatible with this version of MSCL. + // - : Failed to read from the Node. + // - : A connection error has occurred with the parent BaseStation. + WirelessTypes::RegionCode regionCode() const; + + //API Function: quickPing + // Performs a Quick Ping (Short Ping) command on the Node. + // The Base Station itself responds with a quick success/fail on the Node. + // Note: Use the standard command instead of this if you want to obtain RSSI values. + // + //Returns: + // true if the quick ping was successful, false otherwise. + // + //Exceptions: + // - : Failed to determine the protocol version of the BaseStation. + // - : A connection error has occurred with the parent BaseStation. + bool quickPing(); + //API Function: ping - // Performs a Long Ping command on the Node to check the communication between the Base Station and the Node + // Performs a Long Ping command on the Node to check the communication between the Base Station and the Node. + // The response to this command contains the Node and BaseStation RSSI values. + // Note: You may want to use the command instead of this if RSSI values are not of importance. // //Returns: - // A object that can be queried to get details of the ping command's response + // A object that can be queried to get details of the ping command's response, including RSSI values. // //Exceptions: // - : A connection error has occurred with the parent BaseStation @@ -367,14 +391,17 @@ namespace mscl // See Also: , // //Parameters: - // channelNumber - The channel number (ch1 = 1, ch8 = 8) to balance. - // option - The to use (low, midscale, high). + // mask - The to perform the auto balance command on. + // targetPercent - The percentage (0.0 - 100.0) of the range to balance to (low = 25%, midscale = 50%, high = 75%). + // + //Returns: + // The containing information from the auto balance command. // //Exceptions: - // - : Autobalance is not supported by the Node or channel specified. + // - : Autobalance is not supported by the Node or channel mask specified. // - : Failed to communicate with the Node. // - : A connection error has occurred with the parent BaseStation. - void autoBalance(uint8 channelNumber, WirelessTypes::AutoBalanceOption option); + AutoBalanceResult autoBalance(const ChannelMask& mask, float targetPercent); //API Function: autoCal_shmLink // Performs automatic calibration for the SHM-Link Wireless Node. @@ -624,6 +651,7 @@ namespace mscl // greater than this value, then the node drops into a sleep mode. The Node // will re-enter sync sampling within 2 minutes of the beacon reappearing. // Note: A value of 0 means the lost beacon timeout is disabled. + // See Also: // //Returns: // The lost beacon timeout, in minutes, currently set on the Node. @@ -636,7 +664,7 @@ namespace mscl //API Function: getHardwareGain // Reads the hardware gain of the specified currently set on the Node. - // See Also: + // See Also: , // //Parameters: // mask - The of the hardware gain to read. @@ -652,7 +680,7 @@ namespace mscl //API Function: getHardwareOffset // Reads the hardware offset of the specified currently set on the Node. - // See Also: + // See Also: , // //Parameters: // mask - The of the hardware offset to read. @@ -666,6 +694,22 @@ namespace mscl // - : A connection error has occurred with the parent BaseStation. uint16 getHardwareOffset(const ChannelMask& mask) const; + //API Function: getGaugeFactor + // Reads the gauge factor of the specified currently set on the Node. + // See Also: , + // + //Parameters: + // mask - The of the gauge factor to read. + // + //Returns: + // The gauge factor currently set on the Node for the . + // + //Exceptions: + // - : Gauge Factor is not supported for the provided . + // - : Failed to read from the Node. + // - : A connection error has occurred with the parent BaseStation. + float getGaugeFactor(const ChannelMask& mask) const; + //API Function: getLinearEquation // Gets the linear equation of the specified currently set on the Node. // @@ -769,6 +813,19 @@ namespace mscl // - : Failed to read from the Node. // - : A connection error has occurred with the parent BaseStation. HistogramOptions getHistogramOptions() const; + + //API Function: getActivitySense + // Reads the options currently set on the Node. + // See Also: + // + //Returns: + // The options currently set on the Node. + // + //Exceptions: + // - : ActivitySense configuration is not supported by this Node. + // - : Failed to read from the Node. + // - : A connection error has occurred with the parent BaseStation. + ActivitySense getActivitySense() const; }; } diff --git a/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode_Impl.cpp b/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode_Impl.cpp index 2d81b49b4..f90f45180 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode_Impl.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode_Impl.cpp @@ -7,6 +7,7 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #include +#include "mscl/ScopeHelper.h" #include "mscl/Utils.h" #include "WirelessNode_Impl.h" #include "Features/NodeInfo.h" @@ -18,10 +19,9 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. namespace mscl { - WirelessNode_Impl::WirelessNode_Impl(uint16 nodeAddress, const BaseStation& basestation, WirelessTypes::Frequency nodeFrequency): + WirelessNode_Impl::WirelessNode_Impl(uint16 nodeAddress, const BaseStation& basestation): m_address(checked_cast(nodeAddress, "Node Address")), m_baseStation(basestation), - m_frequency(nodeFrequency), m_eepromHelper(new NodeEepromHelper(this)) { } @@ -88,17 +88,8 @@ namespace mscl } while(!success && (retryCount++ < m_eepromSettings.numRetries)); - //the Node min fw version to support protocol 1.1 - static const Version FW_PROTOCOL_1_1(8, 21); - - if(fwVersion >= FW_PROTOCOL_1_1) - { - return WirelessProtocol::v1_1(); - } - else - { - return WirelessProtocol::v1_0(); - } + //get the protocol to use for the node's fw version + return WirelessProtocol::chooseNodeProtocol(fwVersion); } NodeEeprom& WirelessNode_Impl::eeprom() const @@ -229,14 +220,7 @@ namespace mscl WirelessTypes::Frequency WirelessNode_Impl::frequency() const { - //if we don't know the frequency - if(m_frequency == WirelessTypes::freq_unknown) - { - //read the frequency from eeprom - m_frequency = m_eepromHelper->read_frequency(); - } - - return m_frequency; + return m_eepromHelper->read_frequency(); } Version WirelessNode_Impl::firmwareVersion() const @@ -283,9 +267,9 @@ namespace mscl { config.apply(features(), eeHelper()); - //if the apply succeeded, we need to reset the radio + //if the apply succeeded, we need to cycle the power //for some eeproms to actually take the changes - resetRadio(); + cyclePower(); } uint16 WirelessNode_Impl::getNumDatalogSessions() const @@ -330,6 +314,12 @@ namespace mscl uint32 WirelessNode_Impl::getNumSweeps() const { + //if the node doesn't support limited number of sweeps + if(!features().supportsLimitedDuration()) + { + throw Error_NotSupported("The Number of Sweeps is not supported by this Ndoe."); + } + return m_eepromHelper->read_numSweeps(); } @@ -361,6 +351,12 @@ namespace mscl uint16 WirelessNode_Impl::getLostBeaconTimeout() const { + //if the node doesn't support lost beacon timeout + if(!features().supportsLostBeaconTimeout()) + { + throw Error_NotSupported("Lost Beacon Timeout is not supported by this Node."); + } + return m_eepromHelper->read_lostBeaconTimeout(); } @@ -374,6 +370,11 @@ namespace mscl return m_eepromHelper->read_hardwareOffset(mask); } + float WirelessNode_Impl::getGaugeFactor(const ChannelMask& mask) const + { + return m_eepromHelper->read_gaugeFactor(mask); + } + LinearEquation WirelessNode_Impl::getLinearEquation(const ChannelMask& mask) const { LinearEquation result; @@ -427,6 +428,19 @@ namespace mscl return result; } + ActivitySense WirelessNode_Impl::getActivitySense() const + { + //if the node doesn't support activity sense options + if(!features().supportsActivitySense()) + { + throw Error_NotSupported("ActivitySense configuration is not supported by this Node."); + } + + ActivitySense result; + m_eepromHelper->read_activitySense(result); + return result; + } + /* bool WirelessNode_Impl::shortPing() @@ -440,6 +454,11 @@ namespace mscl } */ + bool WirelessNode_Impl::quickPing() + { + return m_baseStation.node_shortPing(m_address); + } + PingResponse WirelessNode_Impl::ping() { //send the node_ping command to this node's parent base station @@ -458,14 +477,27 @@ namespace mscl //cycle the power on the node by writing a 1 to the CYCLE_POWER location writeEeprom(NodeEepromMap::CYCLE_POWER, Value::UINT16(RESET_NODE)); + + Utils::threadSleep(250); + + //attempt to ping the node a few times to see if its back online + bool pingSuccess = false; + uint8 retries = 0; + while(!pingSuccess && retries <= 5) + { + pingSuccess = ping().success(); + retries++; + } } void WirelessNode_Impl::resetRadio() { static const uint16 RESET_RADIO = 0x02; - //cycle the power on the node by writing a 2 to the CYCLE_POWER location + //cycle the radio on the node by writing a 2 to the CYCLE_POWER location writeEeprom(NodeEepromMap::CYCLE_POWER, Value::UINT16(RESET_RADIO)); + + Utils::threadSleep(100); } void WirelessNode_Impl::changeFrequency(WirelessTypes::Frequency frequency) @@ -479,9 +511,6 @@ namespace mscl //reset the radio on the node to commit the change resetRadio(); - - //update the cached frequency - m_frequency = frequency; } SetToIdleStatus WirelessNode_Impl::setToIdle() @@ -530,42 +559,102 @@ namespace mscl cyclePower(); } - void WirelessNode_Impl::autoBalance(uint8 channelNumber, WirelessTypes::AutoBalanceOption option) + AutoBalanceResult WirelessNode_Impl::autoBalance(const ChannelMask& mask, float targetPercent) { - //verify the node supports autobalance for any channels - if(!features().supportsAutoBalance(channelNumber)) + Utils::checkBounds_min(targetPercent, 0.0f); + Utils::checkBounds_max(targetPercent, 100.0f); + + //attempt a ping first + //(legacy (v1) autobalance doesn't have a response packet, so need to check communication) + if(!ping().success()) { - throw Error_NotSupported("AutoBalance is not supported by channel " + Utils::toStr(channelNumber) + "."); + throw Error_NodeCommunication(nodeAddress()); } - //determine the target value based on the option provided - uint16 targetValue = 0; - switch(option) - { - case WirelessTypes::autoBalance_low: - targetValue = 1024; - break; + //find the eeprom location that the autobalance will adjust + //Note: this also verifies that it is supported for this mask + const EepromLocation& eepromLoc = features().findEeprom(WirelessTypes::chSetting_autoBalance, mask); - case WirelessTypes::autoBalance_midscale: - targetValue = 2048; - break; + //currently, autobalance is always per channel, so get the channel from the mask + uint8 channelNumber = mask.lastChEnabled(); - case WirelessTypes::autoBalance_high: - targetValue = 3072; - break; - - default: - throw Error_NotSupported("The AutoBalanceOption provided is not supported."); - } + AutoBalanceResult result; //perform the autobalance command with the parent base station - m_baseStation.node_autoBalance(m_address, channelNumber, targetValue); + m_baseStation.node_autoBalance(protocol(), m_address, channelNumber, targetPercent, result); - //clear the eeprom cache for the hardware offset location that was affected - ChannelMask mask; - mask.enable(channelNumber); - const EepromLocation& eepromLoc = features().findEeprom(WirelessTypes::chSetting_hardwareOffset, mask); + //clear the cache of the hardware offset eeprom location we adjusted eeprom().clearCacheLocation(eepromLoc.location()); + + Utils::threadSleep(200); + + //if we used the legacy command, we don't get result info, need to do more work to get it + if(result.m_errorCode == WirelessTypes::autobalance_legacyNone) + { + result.m_errorCode = WirelessTypes::autobalance_maybeInvalid; + + //force the read eeprom retries to a minimum of 3 + uint8 startRetries = m_eepromSettings.numRetries; + + //when this goes out of scope, it will change back the original retries value + ScopeHelper writebackRetries(std::bind(&WirelessNode_Impl::readWriteRetries, this, startRetries)); + + //if there are less than 3 retries + if(startRetries < 3) + { + //we want to retry at least a few times + readWriteRetries(3); + } + else + { + //don't need to write back the retries since we didn't make a change + writebackRetries.cancel(); + } + + //read the updated hardware offset from the node + result.m_hardwareOffset = readEeprom(eepromLoc).as_uint16(); + + bool readSensorSuccess = false; + + uint8 readSensorTry = 0; + do + { + //perform the read single sensor command + uint16 sensorVal = 0; + readSensorSuccess = m_baseStation.node_readSingleSensor(m_address, channelNumber, sensorVal); + + if(readSensorSuccess) + { + //find the max bits value of the node + uint32 maxBitsVal = 0; + switch(model()) + { + case WirelessModels::node_vLink: + case WirelessModels::node_sgLink_rgd: + case WirelessModels::node_shmLink: + maxBitsVal = 65536; + break; + + default: + maxBitsVal = 4096; + break; + } + + //calculate and store the percent achieved + result.m_percentAchieved = static_cast(sensorVal) / static_cast(maxBitsVal) * 100.0f; + } + + readSensorTry++; + } + while(!readSensorSuccess && readSensorTry <= 3); + + if(readSensorSuccess) + { + result.m_errorCode = WirelessTypes::autobalance_success; + } + } + + return result; } AutoCalResult_shmLink WirelessNode_Impl::autoCal_shmLink() @@ -580,7 +669,8 @@ namespace mscl } //verify the node is the correct model - if(model != WirelessModels::node_shmLink2) + if(model != WirelessModels::node_shmLink2 && + model != WirelessModels::node_shmLink2_cust1) { throw Error_NotSupported("autoCal_shmLink is not supported by this Node's model."); } diff --git a/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode_Impl.h b/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode_Impl.h index 1272ae343..4b6d7c4d0 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode_Impl.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/WirelessNode_Impl.h @@ -10,8 +10,10 @@ MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. #include "WirelessChannel.h" #include "RadioFeatures.h" #include "mscl/Version.h" -#include "Commands/AutoCal.h" +#include "Commands/AutoBalanceResult.h" +#include "Commands/AutoCalResult.h" #include "Commands/WirelessProtocol.h" +#include "Configuration/ActivitySense.h" #include "Configuration/ConfigIssue.h" #include "Configuration/FatigueOptions.h" #include "Configuration/HistogramOptions.h" @@ -44,8 +46,7 @@ namespace mscl //Parameters: // nodeAddress - the node address of the node // basestation - the node's parent Base Station - // nodeFrequency - the that this node is believed to be on. - WirelessNode_Impl(uint16 nodeAddress, const BaseStation& basestation, WirelessTypes::Frequency nodeFrequency); + WirelessNode_Impl(uint16 nodeAddress, const BaseStation& basestation); private: //Variable: m_address @@ -60,10 +61,6 @@ namespace mscl // The eeprom settings to use for the object. NodeEepromSettings m_eepromSettings; - //Variable: m_frequency - // The that this Node is believed to be on. - mutable WirelessTypes::Frequency m_frequency; - //Variable: m_protocol // The containing all of the protocol commands and info for this Node. mutable std::unique_ptr m_protocol; @@ -420,20 +417,31 @@ namespace mscl //Function: getHardwareOffset // Reads the hardware offset of the specified currently set on the Node. - // See Also: // //Parameters: // mask - The of the hardware offset to read. // - //Returns: - // The hardware offset currently set on the Node for the . - // //Exceptions: // - : Hardware offset is not supported for the provided . // - : Failed to read from the Node. // - : A connection error has occurred with the parent BaseStation. uint16 getHardwareOffset(const ChannelMask& mask) const; + //Function: getGaugeFactor + // Reads the gauge factor of the specified currently set on the Node. + // + //Parameters: + // mask - The of the gauge factor to read. + // + //Returns: + // The gauge factor currently set on the Node for the . + // + //Exceptions: + // - : Gauge Factor is not supported for the provided . + // - : Failed to read from the Node. + // - : A connection error has occurred with the parent BaseStation. + float getGaugeFactor(const ChannelMask& mask) const; + //Function: getLinearEquation // Gets the linear equation of the specified currently set on the Node. // @@ -506,7 +514,23 @@ namespace mscl // - : A connection error has occurred with the parent BaseStation. HistogramOptions getHistogramOptions() const; + //Function: getActivitySense + // Reads the options currently set on the Node. + // + //Exceptions: + // - : ActivitySense configuration is not supported by this Node. + // - : Failed to read from the Node. + // - : A connection error has occurred with the parent BaseStation. + ActivitySense getActivitySense() const; + public: + //Function: quickPing + // Performs a Quick Ping (Short Ping) command on the Node. + // + //Returns: + // true if the quick ping was successful, false otherwise. + bool quickPing(); + //Function: ping // Performs a Long Ping command on the Node to check the communication between the Base Station and the Node. // @@ -597,14 +621,17 @@ namespace mscl // Performs an Auto Balance command on a specified channel on the Node. // //Parameters: - // channelNumber - The channel number (ch1 = 1, ch8 = 8) to balance. - // option - The to use (low, midscale, high). + // mask - The to perform the auto balance command on. + // targetPercent - The percentage (0.0 - 100.0) of the range to balance to. + // + //Returns: + // The containing information from the auto balance command. // //Exceptions: // - : Autobalance is not supported by the Node or channel specified. // - : Failed to communicate with the Node. // - : A connection error has occurred with the parent BaseStation. - void autoBalance(uint8 channelNumber, WirelessTypes::AutoBalanceOption option); + AutoBalanceResult autoBalance(const ChannelMask& mask, float targetPercent); //Function: autoCal_shmLink // Performs automatic calibration for the SHM-Link Wireless Node. diff --git a/MSCL/source/mscl/MicroStrain/Wireless/WirelessTypes.cpp b/MSCL/source/mscl/MicroStrain/Wireless/WirelessTypes.cpp index 7a8f09570..f6fb36ce4 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/WirelessTypes.cpp +++ b/MSCL/source/mscl/MicroStrain/Wireless/WirelessTypes.cpp @@ -161,7 +161,49 @@ namespace mscl case WirelessTypes::region_usa: case WirelessTypes::region_brazil: default: + return WirelessTypes::power_20dBm; + } + } + + WirelessTypes::TransmitPower WirelessTypes::legacyToTransmitPower(WirelessTypes::LegacyTransmitPower legacyVal) + { + switch(legacyVal) + { + case WirelessTypes::legacyPower_5dBm: + return WirelessTypes::power_5dBm; + + case WirelessTypes::legacyPower_0dBm: + return WirelessTypes::power_0dBm; + + case WirelessTypes::legacyPower_10dBm: + return WirelessTypes::power_10dBm; + + case WirelessTypes::legacyPower_16dBm: return WirelessTypes::power_16dBm; + + default: + return static_cast(legacyVal); + } + } + + WirelessTypes::LegacyTransmitPower WirelessTypes::transmitPowerToLegacy(WirelessTypes::TransmitPower power) + { + switch(power) + { + case WirelessTypes::power_5dBm: + return WirelessTypes::legacyPower_5dBm; + + case WirelessTypes::power_0dBm: + return WirelessTypes::legacyPower_0dBm; + + case WirelessTypes::power_10dBm: + return WirelessTypes::legacyPower_10dBm; + + case WirelessTypes::power_16dBm: + return WirelessTypes::legacyPower_16dBm; + + default: + throw Error("Attempting to convert a transmit power (" + Utils::toStr(power) + ") without a legacy equivalent."); } } } \ No newline at end of file diff --git a/MSCL/source/mscl/MicroStrain/Wireless/WirelessTypes.h b/MSCL/source/mscl/MicroStrain/Wireless/WirelessTypes.h index 2ad2a8b50..a0462cc23 100644 --- a/MSCL/source/mscl/MicroStrain/Wireless/WirelessTypes.h +++ b/MSCL/source/mscl/MicroStrain/Wireless/WirelessTypes.h @@ -199,17 +199,19 @@ namespace mscl //API Enums: TransmitPower // Represents the transmit powers that can be used for Wireless Devices. // - // power_16dBm - 25619 - 16 dBm (39 mw) - // power_10dBm - 25615 - 10 dBm (10 mw) - // power_5dBm - 25611 - 5 dBm (3 mw) - // power_0dBm - 25607 - 0 dBm (1 mw) + // power_20dBm - 20 - 20 dBm (100 mw) + // power_16dBm - 16 - 16 dBm (39 mw) + // power_10dBm - 10 - 10 dBm (10 mw) + // power_5dBm - 5 - 5 dBm (3 mw) + // power_0dBm - 0 - 0 dBm (1 mw) //===================================================================================================== enum TransmitPower { - power_16dBm = 25619, - power_10dBm = 25615, - power_5dBm = 25611, - power_0dBm = 25607 + power_20dBm = 20, + power_16dBm = 16, + power_10dBm = 10, + power_5dBm = 5, + power_0dBm = 0 }; //===================================================================================================== @@ -575,6 +577,8 @@ namespace mscl // chSetting_unit - 4 - Unit // chSetting_equationType - 5 - Equation Type // chSetting_hardwareOffset - 6 - Hardware Offset + // chSetting_autoBalance - 7 - Autobalance Function + // chSetting_gaugeFactor - 8 - Gauge Factor enum ChannelGroupSetting { chSetting_hardwareGain = 0, @@ -583,16 +587,30 @@ namespace mscl chSetting_linearEquation = 3, chSetting_unit = 4, chSetting_equationType = 5, - chSetting_hardwareOffset = 6 + chSetting_hardwareOffset = 6, + chSetting_autoBalance = 7, + chSetting_gaugeFactor = 8 }; - //API Enum: AutoBalanceOption - // The options available to balance to for the Auto Balance Node command. - enum AutoBalanceOption + //API Enum: AutoBalanceErrorFlag + // The possible completion flags for the AutoBalance Wireless Node function. + // + // autobalance_success - 0 - AutoBalance was successful. + // autobalance_maybeInvalid - 1 - AutoBalance completed, but the values look suspicious. + // autobalance_notSupportedByNode - 2 - AutoBalance is not supported by the Node. + // autobalance_notSupportedByCh - 3 - AutoBalance is not supported by the channel. + // autobalance_targetOutOfRange - 4 - The target balance value is out of range for the channel. + // autobalance_legacyNone - 998 - The legacy AutoBalance command was used, so no info was returned. + // autobalance_notComplete - 999 - AutoBalance has not yet completed. + enum AutoBalanceErrorFlag { - autoBalance_low = 0, - autoBalance_midscale = 1, - autoBalance_high = 2 + autobalance_success = 0, + autobalance_maybeInvalid = 1, + autobalance_notSupportedByNode = 2, + autobalance_notSupportedByCh = 3, + autobalance_targetOutOfRange = 4, + autobalance_legacyNone = 998, + autobalance_notComplete = 999 }; //API Enum: AutoCalCompletionFlag @@ -603,9 +621,9 @@ namespace mscl // autocal_notComplete - 999 - AutoCal has not yet completed. enum AutoCalCompletionFlag { - autocal_success = 0, - autocal_maybeInvalid = 1, - autocal_notComplete = 999 + autocal_success = 0, + autocal_maybeInvalid = 1, + autocal_notComplete = 999 }; //API Enum: AutoCalErrorFlag @@ -621,6 +639,19 @@ namespace mscl autocalError_sensorShorted = 2 }; + //API Enum: FatigueMode + // The different modes a Fatigue Node can operate in. + // + // fatigueMode_angleStrain - 0 - Standard angle strain mode: can enter specific angles to sample. + // fatigueMode_distributedAngle - 1 - Distributed angle mode: can enter a low, high, and # of angles (4-16) to sample. + // fatigueMode_rawGaugeStrain - 2 - Raw Gauge Strain mode: sends the raw strain sensor data. + enum FatigueMode + { + fatigueMode_angleStrain = 0, + fatigueMode_distributedAngle = 1, + fatigueMode_rawGaugeStrain = 2 + }; + public: //API Typedefs: // DataCollectionMethods - A vector of enums. @@ -629,7 +660,8 @@ namespace mscl // SamplingModes - A vector of enums. // DefaultModes - A vector of enums. // TransmitPowers - A vector of enums. - // ChannelGroupSettings - A vectof of enums. + // ChannelGroupSettings - A vector of enums. + // FatigueModes - A vector of enums. typedef std::vector DataCollectionMethods; typedef std::vector DataFormats; typedef std::vector WirelessSampleRates; @@ -637,12 +669,30 @@ namespace mscl typedef std::vector DefaultModes; typedef std::vector TransmitPowers; typedef std::vector ChannelGroupSettings; + typedef std::vector FatigueModes; //API Constant: UNKNOWN_RSSI = 999 // The value given for an unknown RSSI value. static const int16 UNKNOWN_RSSI = 999; #ifndef SWIG + //===================================================================================================== + //Enums: LegacyTransmitPower + // Represents the legacy transmit powers supported by older devices. + // + // legacyPower_16dBm - 25619 - 16 dBm (39 mw) + // legacyPower_10dBm - 25615 - 10 dBm (10 mw) + // legacyPower_5dBm - 25611 - 5 dBm (3 mw) + // legacyPower_0dBm - 25607 - 0 dBm (1 mw) + //===================================================================================================== + enum LegacyTransmitPower + { + legacyPower_16dBm = 25619, + legacyPower_10dBm = 25615, + legacyPower_5dBm = 25611, + legacyPower_0dBm = 25607 + }; + //Function: dataTypeSize // Gets the byte size of the data type passed in // @@ -712,6 +762,29 @@ namespace mscl //Returns: // The max . static WirelessTypes::TransmitPower maxTransmitPower(WirelessTypes::RegionCode region); + + //Function: legacyToTransmitPower + // Converts the given to the equivalent. + // + //Parameters: + // legacyVal - the to convert. + // + //Returns: + // The equivalent of the legacy transmit power. + static WirelessTypes::TransmitPower legacyToTransmitPower(WirelessTypes::LegacyTransmitPower legacyVal); + + //Function: transmitPowerToLegacy + // Converts the given to the equivalent. + // + //Parameters: + // power - the to convert. + // + //Returns: + // The equivalent of the current transmit power. + // + //Exceptions: + // - : Invalid transmit power. + static WirelessTypes::LegacyTransmitPower transmitPowerToLegacy(WirelessTypes::TransmitPower power); #endif }; } \ No newline at end of file diff --git a/MSCL/source/mscl/ScopeHelper.cpp b/MSCL/source/mscl/ScopeHelper.cpp new file mode 100644 index 000000000..5cfc6c413 --- /dev/null +++ b/MSCL/source/mscl/ScopeHelper.cpp @@ -0,0 +1,29 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#include "stdafx.h" +#include "ScopeHelper.h" + +namespace mscl +{ + ScopeHelper::ScopeHelper(std::function scopeFunction): + m_outOfScopeFunction(scopeFunction), + m_canceled(false) + { + } + + ScopeHelper::~ScopeHelper() + { + if(!m_canceled) + { + m_outOfScopeFunction(); + } + } + + void ScopeHelper::cancel() + { + m_canceled = true; + } +} \ No newline at end of file diff --git a/MSCL/source/mscl/ScopeHelper.h b/MSCL/source/mscl/ScopeHelper.h new file mode 100644 index 000000000..6012c605b --- /dev/null +++ b/MSCL/source/mscl/ScopeHelper.h @@ -0,0 +1,38 @@ +/******************************************************************************* +Copyright(c) 2015 LORD Corporation. All rights reserved. + +MIT Licensed. See the included LICENSE.txt for a copy of the full MIT License. +*******************************************************************************/ +#pragma once + +#include +#include +#include "Types.h" + +namespace mscl +{ + //Class: ScopeHelper + // Class that allows a function to be run when this object goes out of scope. + class ScopeHelper + { + private: + //Variable: m_outOfScopeFunction + // The function to run when the ScopeHelper goes out of scope. + std::function m_outOfScopeFunction; + + //Variable: m_canceled + // Whether the scope function has been canceled or not. + bool m_canceled; + + ScopeHelper(); //default constructor disabled + ScopeHelper(const ScopeHelper&); //copy constructor disabled + ScopeHelper& operator=(const ScopeHelper&); //assignment operator disabled + + public: + ScopeHelper(std::function scopeFunction); + + ~ScopeHelper(); + + void cancel(); + }; +} \ No newline at end of file diff --git a/MSCL/source/mscl/Wrapper/MSCL_Exceptions.i b/MSCL/source/mscl/Wrapper/MSCL_Exceptions.i index 207e8e23f..137ca8e90 100644 --- a/MSCL/source/mscl/Wrapper/MSCL_Exceptions.i +++ b/MSCL/source/mscl/Wrapper/MSCL_Exceptions.i @@ -869,6 +869,8 @@ %catches(mscl::Error_NoData) mscl::WirelessNodeConfig::timeBetweenBursts() const; %catches(mscl::Error_NoData) mscl::WirelessNodeConfig::lostBeaconTimeout() const; %catches(mscl::Error_NoData) mscl::WirelessNodeConfig::hardwareGain(const ChannelMask& mask) const; +%catches(mscl::Error_NoData) mscl::WirelessNodeConfig::hardwareOffset(const ChannelMask& mask) const; +%catches(mscl::Error_NoData) mscl::WirelessNodeConfig::gaugeFactor(const ChannelMask& mask) const; %catches(mscl::Error_NoData) mscl::WirelessNodeConfig::filterSettlingTime(const ChannelMask& mask) const; %catches(mscl::Error_NoData) mscl::WirelessNodeConfig::thermocoupleType(const ChannelMask& mask) const; %catches(mscl::Error_NoData) mscl::WirelessNodeConfig::linearEquation(const ChannelMask& mask) const; @@ -876,9 +878,11 @@ %catches(mscl::Error_NoData) mscl::WirelessNodeConfig::equation(const ChannelMask& mask) const; %catches(mscl::Error_NoData) mscl::WirelessNodeConfig::fatigueOptions() const; %catches(mscl::Error_NoData) mscl::WirelessNodeConfig::histogramOptions() const; +%catches(mscl::Error_NoData) mscl::WirelessNodeConfig::activitySense() const; //WirelessNode %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::features() const; +%catches(mscl::Error_Connection, mscl::Error_Communication) mscl::WirelessNode::quickPing(); %catches(mscl::Error_Connection) mscl::WirelessNode::ping(); %catches(mscl::Error_Connection) mscl::WirelessNode::sleep(); %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::readEeprom(uint16 location) const; @@ -893,11 +897,12 @@ %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::microcontroller() const; %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::radioFeatures() const; %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::dataStorageSize() const; +%catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::regionCode() const; %catches(mscl::Error_Connection) mscl::WirelessNode::setToIdle(); %catches(mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::erase(); %catches(mscl::Error_InvalidNodeConfig, mscl::Error_Connection) mscl::WirelessNode::startNonSyncSampling(); %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::clearHistogram(); -%catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::autoBalance(uint8 channelNumber, WirelessTypes::AutoBalanceOption option); +%catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::autoBalance(const ChannelMask& mask, float targetPercent); %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::autoCal_shmLink(); %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::verifyConfig(const WirelessNodeConfig& config, ConfigIssues& outIssues) const; %catches(mscl::Error_NotSupported, mscl::Error_InvalidNodeConfig, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::applyConfig(const WirelessNodeConfig& config); @@ -917,6 +922,7 @@ %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::getLostBeaconTimeout() const; %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::getHardwareGain(const ChannelMask& mask) const; %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::getHardwareOffset(const ChannelMask& mask) const; +%catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::getGaugeFactor(const ChannelMask& mask) const; %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::getFilterSettlingTime(const ChannelMask& mask) const; %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::getThermocoupleType(const ChannelMask& mask) const; %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::getLinearEquation(const ChannelMask& mask) const; @@ -924,6 +930,8 @@ %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::getEquation(const ChannelMask& mask) const; %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::getFatigueOptions() const; %catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::getHistogramOptions() const; +%catches(mscl::Error_NotSupported, mscl::Error_NodeCommunication, mscl::Error_Connection) mscl::WirelessNode::getActivitySense() const; + //NodeFeatures %catches(mscl::Error_NotSupported) mscl::NodeFeatures::minHardwareGain() const; @@ -949,6 +957,9 @@ %catches(mscl::Error_InertialCmdFailed, mscl::Error_Timeout, mscl::Error_NotSupported, mscl::Error_Connection) mscl::InertialNode::enableDataStream(InertialTypes::InertialCategory category, bool enable); %catches(mscl::Error_Timeout, mscl::Error_InertialCmdFailed, mscl::Error_Connection) mscl::InertialNode::setToIdle(); %catches(mscl::Error_Timeout, mscl::Error_InertialCmdFailed, mscl::Error_Connection) mscl::InertialNode::resume(); +%catches(mscl::Error_InertialCmdFailed, mscl::Error_Timeout, mscl::Error_NotSupported, mscl::Error_Connection) mscl::InertialNode::getSensorToVehicleTransformation(); +%catches(mscl::Error_InertialCmdFailed, mscl::Error_Timeout, mscl::Error_NotSupported, mscl::Error_Connection) mscl::InertialNode::setSensorToVehicleTransformation(const EulerAngles& angles); + //Value %catches(mscl::Error_BadDataType) mscl::Value::as_float() const; diff --git a/MSCL/source/mscl/Wrapper/MSCL_Main_Interface.i b/MSCL/source/mscl/Wrapper/MSCL_Main_Interface.i index 255671404..62868c0fb 100644 --- a/MSCL/source/mscl/Wrapper/MSCL_Main_Interface.i +++ b/MSCL/source/mscl/Wrapper/MSCL_Main_Interface.i @@ -90,6 +90,7 @@ #include "../MicroStrain/Wireless/BaseStation.h" #include "../MicroStrain/Wireless/Configuration/BaseStationEepromMap.h" #include "../MicroStrain/Wireless/Configuration/ConfigIssue.h" +#include "../MicroStrain/Wireless/Configuration/ActivitySense.h" #include "../MicroStrain/Wireless/Configuration/FatigueOptions.h" #include "../MicroStrain/Wireless/Configuration/HistogramOptions.h" #include "../MicroStrain/Wireless/DatalogDownloader.h" @@ -108,13 +109,16 @@ #include "../MicroStrain/Wireless/SyncNetworkInfo.h" #include "../MicroStrain/Wireless/SyncSamplingNetwork.h" #include "../MicroStrain/Wireless/StructuralHealth.h" -#include "../MicroStrain/Wireless/Commands/AutoCal.h" +#include "../MicroStrain/Wireless/Commands/AutoBalanceResult.h" +#include "../MicroStrain/Wireless/Commands/AutoCalResult.h" #include "../MicroStrain/Wireless/Commands/BaseStation_BeaconStatus.h" #include "../MicroStrain/Wireless/Commands/LongPing.h" #include "../MicroStrain/Wireless/Commands/SetToIdleStatus.h" #include "../MicroStrain/Wireless/Features/ChannelGroup.h" #include "../MicroStrain/Wireless/Features/NodeFeatures.h" #include "../MicroStrain/Wireless/Features/BaseStationFeatures.h" +#include "../MicroStrain/Inertial/EulerAngles.h" +#include "../MicroStrain/Inertial/PositionOffset.h" #include "../MicroStrain/Inertial/InertialModels.h" #include "../MicroStrain/Inertial/InertialTypes.h" #include "../MicroStrain/Inertial/InertialChannel.h" @@ -122,6 +126,7 @@ #include "../MicroStrain/Inertial/Packets/InertialDataPacket.h" #include "../MicroStrain/Inertial/InertialDataPoint.h" #include "../MicroStrain/Inertial/InertialNodeInfo.h" +#include "../MicroStrain/Inertial/Features/InertialNodeFeatures.h" #include "../MicroStrain/Inertial/InertialNode.h" #include "../MicroStrain/Inertial/Packets/InertialPacket.h" %} @@ -150,6 +155,7 @@ %include "../MicroStrain/DataPoint.h" %include "../MicroStrain/Wireless/ChannelMask.h" %include "../MicroStrain/Wireless/Configuration/ConfigIssue.h" +%include "../MicroStrain/Wireless/Configuration/ActivitySense.h" %include "../MicroStrain/Wireless/Configuration/FatigueOptions.h" %include "../MicroStrain/Wireless/Configuration/HistogramOptions.h" %include "../MicroStrain/Wireless/WirelessModels.h" @@ -167,7 +173,8 @@ %include "../MicroStrain/Wireless/LoggedDataSweep.h" %include "../MicroStrain/Wireless/RadioFeatures.h" %include "../MicroStrain/Wireless/Configuration/WirelessNodeConfig.h" -%include "../MicroStrain/Wireless/Commands/AutoCal.h" +%include "../MicroStrain/Wireless/Commands/AutoBalanceResult.h" +%include "../MicroStrain/Wireless/Commands/AutoCalResult.h" %include "../MicroStrain/Wireless/Commands/LongPing.h" %include "../MicroStrain/Wireless/Commands/SetToIdleStatus.h" %include "../MicroStrain/Wireless/WirelessNode.h" @@ -177,6 +184,8 @@ %include "../MicroStrain/Wireless/SyncSamplingNetwork.h" %include "../MicroStrain/Wireless/Features/NodeFeatures.h" %include "../MicroStrain/Wireless/Features/BaseStationFeatures.h" +%include "../MicroStrain/Inertial/EulerAngles.h" +%include "../MicroStrain/Inertial/PositionOffset.h" %include "../MicroStrain/Inertial/InertialModels.h" %include "../MicroStrain/Inertial/InertialTypes.h" %include "../MicroStrain/Inertial/InertialChannel.h" @@ -185,6 +194,7 @@ %include "../MicroStrain/Inertial/InertialDataPoint.h" %include "../MicroStrain/Inertial/Packets/InertialDataPacket.h" %include "../MicroStrain/Inertial/InertialNodeInfo.h" +%include "../MicroStrain/Inertial/Features/InertialNodeFeatures.h" %include "../MicroStrain/Inertial/InertialNode.h" namespace std @@ -205,6 +215,7 @@ namespace std %template(DefaultModes) vector; %template(TransmitPowers) vector; %template(ChannelGroupSettings) vector; + %template(FatigueModes) vector; %template(SampleRates) vector; %template(ConfigIssues) vector; %template(ChannelFields) vector; @@ -214,7 +225,6 @@ namespace std %template(DamageAngles) map; %template(SnCurveSegments) map; - %ignore vector::vector(size_type); //no default constructor %ignore vector::resize; //no default constructor %template(Bins) vector; diff --git a/MSCL_Examples/Inertial/MATLAB/parseData.m b/MSCL_Examples/Inertial/MATLAB/parseData.m new file mode 100644 index 000000000..b5957784d --- /dev/null +++ b/MSCL_Examples/Inertial/MATLAB/parseData.m @@ -0,0 +1,62 @@ +function parseData() + +% MSCL Example: ParseData +% This example shows how to parse incoming data from an Inertial Device. +% This example does not start a Node sampling. To receive data, a Node +% must be put into a sampling mode. + + +% import MSCL .NET library (make sure path is correct for your system) +msclInfo = NET.addAssembly('C:\Program Files\MATLAB\MSCL\MSCL_Managed.dll'); + + +%TODO: change these constants to match your setup + +COM_PORT = 'COM4'; + +try + % create a Serial Connection with the specified COM Port, default baud rate of 921600 + connection = mscl.Connection.Serial(COM_PORT); + + % create an instance of MATLAB onCleanup class to gracefully disconnect from COM port when + % this object is cleared, for instance if matlab encounters an error + % before the connection is closed. + cleanupConnection = onCleanup(@()connection.disconnect); + + % create an InertialNode with the connection + node = mscl.InertialNode(connection); + + while true + try + % get the next data packet from the node, with a timeout of 500 milliseconds + packet = node.getNextDataPacket(500); + + % print out the data + display('Packet received: '); + + % iterate over all the data points in the packet + for i = 1:packet.data().Count(), + dataPoint = packet.data().Item(i-1); + display(['dataPoint: ',num2str(dataPoint.as_float)]) % display dataPoint value as string + end + + %if the dataPoint is invalid + if dataPoint.valid() == false, + display('Invalid data point') + end + + catch err + display(err.message) + clearvars cleanupConnnection % performs cleanup on connection + break % exits while loop upon error + end + end + +catch err + display(err.message) + clearvars cleanupConnnection % performs cleanup on connection +end + +end + + diff --git a/MSCL_Examples/Wireless/C++/MSCL_Examples_C++/ConfigureNode/ConfigureNode.cpp b/MSCL_Examples/Wireless/C++/MSCL_Examples_C++/ConfigureNode/ConfigureNode.cpp index cc1b3e75f..5be9add8d 100644 --- a/MSCL_Examples/Wireless/C++/MSCL_Examples_C++/ConfigureNode/ConfigureNode.cpp +++ b/MSCL_Examples/Wireless/C++/MSCL_Examples_C++/ConfigureNode/ConfigureNode.cpp @@ -2,7 +2,7 @@ // This example shows how to get and set the configuration options for a Wireless Node. // Warning: Running this example will change the configuration on the Wireless Node. // -//Updated: 04/01/2015 +//Updated: 11/02/2015 #include using namespace std; @@ -30,16 +30,36 @@ void getCurrentConfig(const mscl::WirelessNode& node) cout << "Total active channels: " << node.getActiveChannels().count() << endl; cout << "# of sweeps: " << node.getNumSweeps() << endl; - //get a list of the supported channels - mscl::WirelessChannels supportedChannels = node.channels(); + //If a configuration function requires a ChannelMask parameter, this indicates that the + //option may affect 1 or more channels on the Node. For instance, a hardware gain may + //affect ch1 and ch2 with just 1 setting. If you know the mask for your Node, you can just provide + //that mask when asking for the configuration. If you want to programatically determine + //the mask for each setting, you can ask for the Node's ChannelGroups. See below. - //loop through all of the channels - for(const auto& channel : supportedChannels) + //get the ChannelGroups that the node supports + mscl::ChannelGroups chGroups = node.features().channelGroups(); + + //iterate over each channel group + for(const auto& group : chGroups) { - //print out some information about the channels - cout << "Channel #: " << static_cast(channel.first) << endl; - cout << "Slope: " << channel.second->getLinearEquation().slope() << endl; - cout << "Offset: " << channel.second->getLinearEquation().offset() << endl; + //get all of the settings for this group (ie. may contain linear equation and hardware gain). + mscl::WirelessTypes::ChannelGroupSettings groupSettings = group.settings(); + + //iterate over each setting for this group + for(auto setting : groupSettings) + { + //if the group contains the linear equation setting + if(setting == mscl::WirelessTypes::chSetting_linearEquation) + { + //we can now pass the channel mask (group.channels()) for this group to the node.getLinearEquation function. + //Note: once this channel mask is known for a specific node (+ fw version), it should never change + mscl::LinearEquation le = node.getLinearEquation(group.channels()); + + cout << "Linear Equation for: " << group.name() << endl; + cout << "Slope: " << le.slope() << endl; + cout << "Offset: " << le.offset() << endl; + } + } } } @@ -58,7 +78,7 @@ void setCurrentConfig(mscl::WirelessNode& node) mscl::WirelessNodeConfig config; //set the configuration options that we want to change - config.bootMode(mscl::WirelessTypes::bootMode_normal); + config.defaultMode(mscl::WirelessTypes::defaultMode_idle); config.inactivityTimeout(7200); config.samplingMode(mscl::WirelessTypes::samplingMode_sync); config.sampleRate(mscl::WirelessTypes::sampleRate_256Hz); @@ -83,7 +103,7 @@ void setCurrentConfig(mscl::WirelessNode& node) else { //apply the configuration to the Node - // Note that if this writes multiple options to the Node. + // Note that this writes multiple options to the Node. // If an Error_NodeCommunication exception is thrown, it is possible that // some options were successfully applied, while others failed. // It is recommended to keep calling applyConfig until no exception is thrown. diff --git a/MSCL_Examples/Wireless/C++/MSCL_Examples_C++/ParseData/ParseData.cpp b/MSCL_Examples/Wireless/C++/MSCL_Examples_C++/ParseData/ParseData.cpp index 4819086e2..c63827cd7 100644 --- a/MSCL_Examples/Wireless/C++/MSCL_Examples_C++/ParseData/ParseData.cpp +++ b/MSCL_Examples/Wireless/C++/MSCL_Examples_C++/ParseData/ParseData.cpp @@ -3,7 +3,7 @@ // This example does not start a Node sampling. To receive data, a Node // must be put into a sampling mode (Sync Sampling, Low Duty Cycle, etc.) // -//Updated: 10/01/2014 +//Updated: 11/02/2015 #include using namespace std; @@ -27,9 +27,6 @@ int main(int argc, char **argv) //endless loop of reading in data while(true) { - //This example uses the "getData()" command. This command gets ALL of the available DataSweeps in the buffer. If the returned contains is empty, no data exists. - //Alternatively, you may use the "getNextData()" command to get a single DataSweep from the buffer. If no data exists in this case, an exception will be thrown. - //get all the data sweeps that have been collected by the BaseStation, with a timeout of 500 milliseconds mscl::DataSweeps sweeps = base.getData(500); diff --git a/MSCL_Examples/Wireless/C++/MSCL_Examples_C++/StopNode/StopNode.cpp b/MSCL_Examples/Wireless/C++/MSCL_Examples_C++/StopNode/StopNode.cpp index b962cd52d..9c81816f3 100644 --- a/MSCL_Examples/Wireless/C++/MSCL_Examples_C++/StopNode/StopNode.cpp +++ b/MSCL_Examples/Wireless/C++/MSCL_Examples_C++/StopNode/StopNode.cpp @@ -4,7 +4,7 @@ // idle state so that it can be communicated with. // Note: Stopping a Node usually takes a few seconds, but may take up to 2 minutes. // -//Updated: 09/15/2014 +//Updated: 11/02/2015 #include using namespace std; @@ -31,42 +31,42 @@ int main(int argc, char **argv) //create a WirelessNode with the BaseStation mscl::WirelessNode node(NODE_ADDRESS, baseStation); - //call the stop function and get the resulting StopNodeStatus object - // Note: This starts the stop node command, which is an ongoing operation. The StopNodeStatus should be queried for progress. - mscl::StopNodeStatus stopStatus = node.stop(); + //call the set to idle function and get the resulting SetToIdleStatus object + // Note: This starts the set to idle node command, which is an ongoing operation. The SetToIdleStatus should be queried for progress. + mscl::SetToIdleStatus status = node.setToIdle(); - cout << "Stopping Node"; + cout << "Setting Node to Idle"; - //using the StopNodeStatus object, check if the Stop Node operation is complete. - // Note: we are specifying a timeout of 300 millisecond here which is the maximum - // amount of time that the complete function will block if the Stop Node + //using the SetToIdleStatus object, check if the Set to Idle operation is complete. + // Note: we are specifying a timeout of 300 milliseconds here which is the maximum + // amount of time that the complete function will block if the Set to Idle // operation has not finished. Leaving this blank defaults to a timeout of 10ms. - while(!stopStatus.complete(300)) + while(!status.complete(300)) { - //Note: the Stop Node operation can be canceled by calling stopStatus.cancel() + //Note: the Set to Idle operation can be canceled by calling status.cancel() cout << "."; } - //at this point, the Stop Node operation has completed + //at this point, the Set to Idle operation has completed - //check the result of the Stop Node operation - switch(stopStatus.result()) + //check the result of the Set to Idle operation + switch(status.result()) { - //Stop Node completed successfully - case mscl::StopNodeStatus::stopNodeResult_success: - cout << "Successfully stopped the Node!" << endl; + //completed successfully + case mscl::SetToIdleStatus::setToIdleResult_success: + cout << "Successfully set to idle!" << endl; break; - //Stop Node has been canceled by the user - case mscl::StopNodeStatus::stopNodeResult_canceled: - cout << "Stop Node was canceled!" << endl; + //canceled by the user + case mscl::SetToIdleStatus::setToIdleResult_canceled: + cout << "Set to Idle was canceled!" << endl; break; - //Failed to perform the Stop Node operation - case mscl::StopNodeStatus::stopNodeResult_failed: - default: - cout << "Stop Node has failed!" << endl; - break; + //failed to perform the operation + case mscl::SetToIdleStatus::setToIdleResult_failed: + default: + cout << "Set to Idle has failed!" << endl; + break; } } catch(mscl::Error& e) diff --git a/MSCL_Examples/Wireless/CSharp/MSCL_Examples_CSharp/ConfigureNode/ConfigureNode.cs b/MSCL_Examples/Wireless/CSharp/MSCL_Examples_CSharp/ConfigureNode/ConfigureNode.cs index f44e50a4b..ac5aa3864 100644 --- a/MSCL_Examples/Wireless/CSharp/MSCL_Examples_CSharp/ConfigureNode/ConfigureNode.cs +++ b/MSCL_Examples/Wireless/CSharp/MSCL_Examples_CSharp/ConfigureNode/ConfigureNode.cs @@ -2,7 +2,7 @@ // This example shows how to get and set the configuration options for a Wireless Node. // Warning: Running this example will change the configuration on the Wireless Node. // -//Updated: 04/01/2015 +//Updated: 11/02/2015 //Note: If you are having 'PINVOKE' errors, please make sure the following is true: // -'MSCL_Managed' is added as a Refence for the project (add 'MSCL_Managed.dll') @@ -36,17 +36,36 @@ static void getCurrentConfig(ref mscl.WirelessNode node) Console.WriteLine("Total active channels: " + node.getActiveChannels().count()); Console.WriteLine("# of sweeps: " + node.getNumSweeps()); - //get a list of the supported channels - mscl.WirelessChannels supportedChannels = node.channels(); + //If a configuration function requires a ChannelMask parameter, this indicates that the + //option may affect 1 or more channels on the Node. For instance, a hardware gain may + //affect ch1 and ch2 with just 1 setting. If you know the mask for your Node, you can just provide + //that mask when asking for the configuration. If you want to programatically determine + //the mask for each setting, you can ask for the Node's ChannelGroups. See below. - //loop through all of the channels - foreach(var channel in supportedChannels) - { - //print out some information about the channels - Console.WriteLine("Channel #: " + channel.Key); - Console.WriteLine("Slope: " + channel.Value.getLinearEquation().slope()); - Console.WriteLine("Offset: " + channel.Value.getLinearEquation().offset()); - } + mscl.ChannelGroups chGroups = node.features().channelGroups(); + + //iterate over each channel group + foreach(var group in chGroups) + { + //get all of the settings for this group (ie. may contain linear equation and hardware gain). + mscl.ChannelGroupSettings groupSettings = group.settings(); + + //iterate over each setting for this group + foreach(var setting in groupSettings) + { + //if the group contains the linear equation setting + if(setting == mscl.WirelessTypes.ChannelGroupSetting.chSetting_linearEquation) + { + //we can now pass the channel mask (group.channels()) for this group to the node.getLinearEquation function. + //Note: once this channel mask is known for a specific node (+ fw version), it should never change + mscl.LinearEquation le = node.getLinearEquation(group.channels()); + + Console.WriteLine("Linear Equation for: " + group.name()); + Console.WriteLine("Slope: " + le.slope()); + Console.WriteLine("Offset: " + le.offset()); + } + } + } } //Function: setCurrentConfig @@ -63,7 +82,7 @@ static void setCurrentConfig(ref mscl.WirelessNode node) mscl.WirelessNodeConfig config = new mscl.WirelessNodeConfig(); //set some of the node's configuration options - config.bootMode(mscl.WirelessTypes.BootMode.bootMode_normal); + config.defaultMode(mscl.WirelessTypes.DefaultMode.defaultMode_idle); config.inactivityTimeout(7200); config.samplingMode(mscl.WirelessTypes.SamplingMode.samplingMode_sync); config.sampleRate(mscl.WirelessTypes.WirelessSampleRate.sampleRate_256Hz); diff --git a/MSCL_Examples/Wireless/CSharp/MSCL_Examples_CSharp/ParseData/ParseData.cs b/MSCL_Examples/Wireless/CSharp/MSCL_Examples_CSharp/ParseData/ParseData.cs index 3bff3ece1..c40d11ee2 100644 --- a/MSCL_Examples/Wireless/CSharp/MSCL_Examples_CSharp/ParseData/ParseData.cs +++ b/MSCL_Examples/Wireless/CSharp/MSCL_Examples_CSharp/ParseData/ParseData.cs @@ -3,7 +3,7 @@ // This example does not start a Node sampling. To receive data, a Node // must be put into a sampling mode (Sync Sampling, Low Duty Cycle, etc.) // -//Updated: 10/01/2014 +//Updated: 11/02/2015 //Note: If you are having 'PINVOKE' errors, please make sure the following is true: // -'MSCL_Managed' is added as a Refence for the project (add 'MSCL_Managed.dll') @@ -32,9 +32,6 @@ static void Main(string[] args) //endless loop of reading in data while (true) { - //This example uses the "getData()" command. This command gets ALL of the available DataSweeps in the buffer. If the returned contains is empty, no data exists. - //Alternatively, you may use the "getNextData()" command to get a single DataSweep from the buffer. If no data exists in this case, an exception will be thrown. - //get all of the data sweeps that have been collected by the BaseStation, with a timeout of 500 milliseconds mscl.DataSweeps sweeps = baseStation.getData(500); diff --git a/MSCL_Examples/Wireless/CSharp/MSCL_Examples_CSharp/StopNode/StopNode.cs b/MSCL_Examples/Wireless/CSharp/MSCL_Examples_CSharp/StopNode/StopNode.cs index 53d86f1fe..f01e05d69 100644 --- a/MSCL_Examples/Wireless/CSharp/MSCL_Examples_CSharp/StopNode/StopNode.cs +++ b/MSCL_Examples/Wireless/CSharp/MSCL_Examples_CSharp/StopNode/StopNode.cs @@ -4,7 +4,7 @@ // idle state so that it can be communicated with. // Note: Stopping a Node may take up to a maximum of 2 minutes. // -//Updated: 09/15/2014 +//Updated: 11/02/2015 //Note: If you are having 'PINVOKE' errors, please make sure the following is true: @@ -35,40 +35,40 @@ static void Main(string[] args) //create a WirelessNode with the BaseStation we created mscl.WirelessNode node = new mscl.WirelessNode(NODE_ADDRESS, baseStation); - //call the stop function and get the resulting StopNodeStatus object - mscl.StopNodeStatus stopStatus = node.stop(); + //call the set to idle function and get the resulting SetToIdleStatus object + mscl.SetToIdleStatus status = node.setToIdle(); - Console.Write("Stopping Node"); + Console.Write("Setting Node to Idle"); - //using the StopNodeStatus object, check if the Stop Node operation is complete. + //using the SetToIdleStatus object, check if the Set to Idle operation is complete. // Note: we are specifying a timeout of 300 milliseconds here which is the maximum - // amount of time that the complete function will block if the Stop Node + // amount of time that the complete function will block if the Set to Idle // operation has not finished. Leaving this blank defaults to a timeout of 10ms. - while (!stopStatus.complete(300)) + while (!status.complete(300)) { - //Note: the Stop Node operation can be canceled by calling stopStatus.cancel() + //Note: the Set to Idle operation can be canceled by calling status.cancel() Console.Write("."); } - //at this point, the Stop Node operation has completed + //at this point, the Set to Idle operation has completed - //check the result of the Stop Node operation - switch (stopStatus.result()) + //check the result of the Set to Idle operation + switch (status.result()) { - //Stop Node completed successfully - case mscl.StopNodeStatus.StopNodeResult.stopNodeResult_success: - Console.WriteLine("Successfully stopped the Node!"); + //completed successfully + case mscl.SetToIdleStatus.SetToIdleResult.setToIdleResult_success: + Console.WriteLine("Successfully set to idle!"); break; - //Stop Node has been canceled by the user - case mscl.StopNodeStatus.StopNodeResult.stopNodeResult_canceled: - Console.WriteLine("Stop Node was canceled!"); + //canceled by the user + case mscl.SetToIdleStatus.SetToIdleResult.setToIdleResult_canceled: + Console.WriteLine("Set to Idle was canceled!"); break; - //Failed to perform the Stop Node operation - case mscl.StopNodeStatus.StopNodeResult.stopNodeResult_failed: + //Failed to perform the operation + case mscl.SetToIdleStatus.SetToIdleResult.setToIdleResult_failed: default: - Console.WriteLine("Stop Node has failed!"); + Console.WriteLine("Set to Idle has failed!"); break; } } diff --git a/MSCL_Examples/Wireless/Python/ConfigureNode.py b/MSCL_Examples/Wireless/Python/ConfigureNode.py index 6791a466f..b0b40daea 100644 --- a/MSCL_Examples/Wireless/Python/ConfigureNode.py +++ b/MSCL_Examples/Wireless/Python/ConfigureNode.py @@ -2,7 +2,7 @@ # This example shows how to get and set the configuration options for a Wireless Node. # Warning: Running this example will change the configuration on the Wireless Node. # -# Updated: 04/01/2015 +# Updated: 11/02/2015 # import the mscl library import sys @@ -28,17 +28,33 @@ def getCurrentConfig(node): print "User Inactivity Timeout:", node.getInactivityTimeout(), "seconds" print "Total active channels:", node.getActiveChannels().count() print "# of sweeps:", node.getNumSweeps() - - # get a list of the supported channels - supportedChannels = node.channels() - - # loop through all of the channels - for channel in supportedChannels: - # print out some information about the channels - print "Channel #:", channel - print "Slope:", supportedChannels[channel].getLinearEquation().slope() - print "Offset:", supportedChannels[channel].getLinearEquation().offset() + # If a configuration function requires a ChannelMask parameter, this indicates that the + # option may affect 1 or more channels on the Node. For instance, a hardware gain may + # affect ch1 and ch2 with just 1 setting. If you know the mask for your Node, you can just provide + # that mask when asking for the configuration. If you want to programatically determine + # the mask for each setting, you can ask for the Node's ChannelGroups. See below. + + chGroups = node.features().channelGroups() + + # iterate over each channel group + for group in chGroups: + # get all of the settings for this group (ie. may contain linear equation and hardware gain). + groupSettings = group.settings() + + # iterate over each setting for this group + for setting in groupSettings: + + # if the group contains the linear equation setting + if setting == mscl.WirelessTypes.chSetting_linearEquation: + # we can now pass the channel mask (group.channels()) for this group to the node.getLinearEquation function. + # Note: once this channel mask is known for a specific node (+ fw version), it should never change + le = node.getLinearEquation(group.channels()) + + print "Linear Equation for: ", group.name() + print "Slope: ", le.slope() + print "Offset: ", le.offset() + # Function: setCurrentConfig # This function demonstrates how to change the configuration @@ -53,7 +69,7 @@ def setCurrentConfig(node): config = mscl.WirelessNodeConfig() # set the configuration options that we want to change - config.bootMode(mscl.WirelessTypes.bootMode_normal) + config.defaultMode(mscl.WirelessTypes.defaultMode_idle) config.inactivityTimeout(7200) config.samplingMode(mscl.WirelessTypes.samplingMode_sync) config.sampleRate(mscl.WirelessTypes.sampleRate_256Hz) diff --git a/MSCL_Examples/Wireless/Python/ParseData.py b/MSCL_Examples/Wireless/Python/ParseData.py index bbde18744..70180fd0f 100644 --- a/MSCL_Examples/Wireless/Python/ParseData.py +++ b/MSCL_Examples/Wireless/Python/ParseData.py @@ -3,7 +3,7 @@ # This example does not start a Node sampling. To receive data, a Node # must be put into a sampling mode (Sync Sampling, Low Duty Cycle, etc.) # -# Updated: 02/26/2015 +# Updated: 11/02/2015 # import the mscl library import sys @@ -22,10 +22,6 @@ # endless loop of reading in data while True: - # This example uses the "getData()" command. This command gets ALL - # of the available DataSweeps in the buffer. If the returned contains is empty, no data exists. - # Alternatively, you may use the "getNextData()" command to get a - # single DataSweep from the buffer. If no data exists in this case, an exception will be thrown. # get all of the data sweeps that have been collected by the BaseStation, with a timeout of 500 milliseconds sweeps = baseStation.getData(500) diff --git a/MSCL_Examples/Wireless/Python/StopNode.py b/MSCL_Examples/Wireless/Python/StopNode.py index e0d3e77ca..b9c0ae74f 100644 --- a/MSCL_Examples/Wireless/Python/StopNode.py +++ b/MSCL_Examples/Wireless/Python/StopNode.py @@ -4,7 +4,7 @@ # idle state so that it can be communicated with. # Note: Stopping a Node may take up to a maximum of 2 minutes. # -# Updated: 02/26/2015 +# Updated: 11/02/2015 # import the mscl library import sys @@ -25,32 +25,32 @@ # create a WirelessNode with the BaseStation we created node = mscl.WirelessNode(NODE_ADDRESS, baseStation) - # call the stop function and get the resulting StopNodeStatus object - stopStatus = node.stop() + # call the set to idle function and get the resulting SetToIdleStatus object + status = node.setToIdle() - print "Stopping Node", + print "Setting Node to Idle", - # using the StopNodeStatus object, check if the Stop Node operation is complete. - # Note: we are specifying a timeout of 300 millisecond here which is the maximum - # amount of time that the complete function will block if the Stop Node - # operation has not finished. Leaving this blank defaults to a timeout of 10ms. - while not stopStatus.complete(300): - # Note: the Stop Node operation can be canceled by calling stopStatus.cancel() + # using the SetToIdleStatus object, check if the Set to Idle operation is complete. + # Note: we are specifying a timeout of 300 milliseconds here which is the maximum + # amount of time that the complete function will block if the Set to Idle + # operation has not finished. Leaving this blank defaults to a timeout of 10ms. + while not status.complete(300): + # Note: the Set to Idle operation can be canceled by calling status.cancel() print ".", - # at this point, the Stop Node operation has completed + # at this point, the Set to Idle operation has completed - # check the result of the Stop Node operation - result = stopStatus.result() - if result == mscl.StopNodeStatus.stopNodeResult_success: - # Stop Node completed successfully - print "Successfully stopped the Node!" - elif result == mscl.StopNodeStatus.stopNodeResult_canceled: - # Stop Node has been canceled by the user - print "Stop Node was canceled!" + # check the result of the Set to Idle operation + result = status.result() + if result == mscl.SetToIdleStatus.setToIdleResult_success: + # completed successfully + print "Successfully set to idle!" + elif result == mscl.SetToIdleStatus.setToIdleResult_canceled: + # canceled by the user + print "Set to Idle was canceled!" else: - # Failed to perform the Stop Node operation - print "Stop Node has failed!" + # Failed to perform the operation + print "Set to Idle has failed!" except Exception, e: print "Error:", e diff --git a/MSCL_Examples/readme.txt b/MSCL_Examples/readme.txt index 5642c0a67..ce08a6a3c 100644 --- a/MSCL_Examples/readme.txt +++ b/MSCL_Examples/readme.txt @@ -5,7 +5,6 @@ Example projects are provided for some use cases for MSCL. This does not encompass all features of MSCL. Please refer to the MSCL documentation for more details. -Example code is given in C++, C#, VB, Python, and Labview. Open the "Inertial" directory to view example code for LORD's Inertial product line. Open the "Wireless" directory to view example code for LORD's Wireless product line. diff --git a/MSCL_Managed/MSCL_Managed.csproj b/MSCL_Managed/MSCL_Managed.csproj index 968e789d8..9f2ace66e 100644 --- a/MSCL_Managed/MSCL_Managed.csproj +++ b/MSCL_Managed/MSCL_Managed.csproj @@ -86,7 +86,9 @@ + + @@ -119,9 +121,11 @@ + Code + @@ -134,6 +138,7 @@ + @@ -149,6 +154,7 @@ + diff --git a/MSCL_Managed/Properties/AssemblyInfo.cs b/MSCL_Managed/Properties/AssemblyInfo.cs index 4629bd983..768ae4a95 100644 --- a/MSCL_Managed/Properties/AssemblyInfo.cs +++ b/MSCL_Managed/Properties/AssemblyInfo.cs @@ -34,5 +34,5 @@ // [assembly: AssemblyVersion("1.0.*")] // //update with each release -[assembly: AssemblyVersion("1.9.0.0")] -[assembly: AssemblyFileVersion("1.9.0.0")] +[assembly: AssemblyVersion("1.20.1.0")] +[assembly: AssemblyFileVersion("1.20.1.0")] diff --git a/MSCL_Unit_Tests/MSCL_Unit_Tests.vcxproj b/MSCL_Unit_Tests/MSCL_Unit_Tests.vcxproj index 4b685b9df..f7333091a 100644 --- a/MSCL_Unit_Tests/MSCL_Unit_Tests.vcxproj +++ b/MSCL_Unit_Tests/MSCL_Unit_Tests.vcxproj @@ -302,6 +302,7 @@ + diff --git a/MSCL_Unit_Tests/Test_AutoCal.cpp b/MSCL_Unit_Tests/Test_AutoCal.cpp index 3077b9adc..c1d86fae7 100644 --- a/MSCL_Unit_Tests/Test_AutoCal.cpp +++ b/MSCL_Unit_Tests/Test_AutoCal.cpp @@ -11,6 +11,7 @@ but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the included LICENSE.txt file for a copy of the full GNU General Public License. *****************************************************************************/ +#include "mscl/MicroStrain/Wireless/Commands/AutoCalResult.h" #include "mscl/MicroStrain/Wireless/Commands/AutoCal.h" #include "mscl/MicroStrain/Wireless/Packets/WirelessPacket.h" #include "mscl/MicroStrain/ResponseCollector.h" diff --git a/MSCL_Unit_Tests/Test_BaseStation.cpp b/MSCL_Unit_Tests/Test_BaseStation.cpp index 1aebe0892..813f1e3fa 100644 --- a/MSCL_Unit_Tests/Test_BaseStation.cpp +++ b/MSCL_Unit_Tests/Test_BaseStation.cpp @@ -21,6 +21,7 @@ LICENSE.txt file for a copy of the full GNU General Public License. #include "mscl/MicroStrain/Wireless/Configuration/BaseStationEepromMap.h" #include "mscl/MicroStrain/Wireless/WirelessTypes.h" #include "mscl/MicroStrain/Wireless/Commands/AutoCal.h" +#include "mscl/MicroStrain/Wireless/Commands/AutoCalResult.h" #include "mscl/MicroStrain/Wireless/Commands/WirelessProtocol.h" #include @@ -282,19 +283,6 @@ BOOST_AUTO_TEST_CASE(BaseStation_GetNodeDiscoveries_Empty) BOOST_CHECK_EQUAL(nds.size(), 0); } -BOOST_AUTO_TEST_CASE(BaseStation_cyclePower) -{ - std::shared_ptr connImpl(new mockConnectionImpl); - Connection conn(connImpl); - - //create the base station (loads the info) - BaseStation base(conn); - - //check that the command doesn't throw an exception (succeeded) - //Cycle Power has no response and is an eeprom write, but shouldn't throw an exception - BOOST_CHECK_NO_THROW(base.cyclePower()); -} - BOOST_AUTO_TEST_CASE(BaseStation_changeFrequency_success) { std::shared_ptr baseImpl(new mock_baseStationImpl()); @@ -377,40 +365,6 @@ BOOST_AUTO_TEST_CASE(BaseStation_NodeLongPing_Fail_Timeout) BOOST_CHECK_EQUAL(result.baseRssi(), unknownRssi); } -BOOST_AUTO_TEST_CASE(BaseStation_NodeShortPing_Fail) -{ - std::shared_ptr connImpl(new mockConnectionImpl); - Connection conn(connImpl); - - //create the base station (loads the info) - BaseStation base(conn); - - //build the data to send - ByteStream data; - data.append_uint8(0x21); - connImpl->setResponseBytes(data); - - //check that the short ping returns false - BOOST_CHECK_EQUAL(base.node_shortPing(327), false); -} - -BOOST_AUTO_TEST_CASE(BaseStation_NodeShortPing_Success) -{ - std::shared_ptr connImpl(new mockConnectionImpl); - Connection conn(connImpl); - - //create the base station (loads the info) - BaseStation base(conn); - - //build the data to send - ByteStream data; - data.append_uint8(0x02); - connImpl->setResponseBytes(data); - - //check that the short ping returns true - BOOST_CHECK_EQUAL(base.node_shortPing(327), true); -} - BOOST_AUTO_TEST_CASE(BaseStation_NodeEepromRead_Success) { std::shared_ptr connImpl(new mockConnectionImpl); diff --git a/MSCL_Unit_Tests/Test_BaseStationConfig.cpp b/MSCL_Unit_Tests/Test_BaseStationConfig.cpp index c11aaf858..a981947d4 100644 --- a/MSCL_Unit_Tests/Test_BaseStationConfig.cpp +++ b/MSCL_Unit_Tests/Test_BaseStationConfig.cpp @@ -66,7 +66,8 @@ BOOST_AUTO_TEST_CASE(BaseStationConfig_setSingleValue) c.transmitPower(WirelessTypes::power_10dBm); //expect the single eeprom write - expectWrite(impl, BaseStationEepromMap::TX_POWER_LEVEL, Value::UINT16(WirelessTypes::power_10dBm)); + expectWrite(impl, BaseStationEepromMap::TX_POWER_LEVEL, Value(valueType_int16, (int16)WirelessTypes::power_10dBm)); + expectResetRadio(impl); BOOST_CHECK_NO_THROW(b.applyConfig(c)); } @@ -93,6 +94,7 @@ BOOST_AUTO_TEST_CASE(BaseStationConfig_buttons) expectWrite(impl, BaseStationEepromMap::BUTTON1_SHORT_NODE, Value::UINT16(9354)); expectWrite(impl, BaseStationEepromMap::BUTTON2_LONG_FUNC, Value::UINT16(BaseStationButton::btn_disableBeacon)); expectWrite(impl, BaseStationEepromMap::BUTTON2_LONG_NODE, Value::UINT16(9354)); + expectResetRadio(impl); BOOST_CHECK_NO_THROW(b.applyConfig(c)); } @@ -171,6 +173,7 @@ BOOST_AUTO_TEST_CASE(BaseStationConfig_analogPairing) expectWrite(impl, BaseStationEepromMap::ANALOG_EXCEED_ENABLE, Value::UINT16(0)); expectWrite(impl, BaseStationEepromMap::ANALOG_TIMEOUT_TIME, Value::UINT16(60)); expectWrite(impl, BaseStationEepromMap::ANALOG_TIMEOUT_VOLTAGE, Value::FLOAT(45.942f)); + expectResetRadio(impl); BOOST_CHECK_NO_THROW(b.applyConfig(c)); } @@ -198,5 +201,29 @@ BOOST_AUTO_TEST_CASE(BaseStationConfig_analogPairing_fail) BOOST_CHECK_EQUAL(issues.at(0).id(), ConfigIssue::CONFIG_ANALOG_PAIR); } +BOOST_AUTO_TEST_CASE(BaseStationConfig_legacyTransmitPower) +{ + //Tests setting a single value in the config and writing it to a BaseStation + std::shared_ptr impl(new mock_baseStationImpl()); + BaseStation b(impl); + + std::unique_ptr features; + + //3.2 fw doesn't support the new transmit power values + BaseStationInfo info(Version(3, 2), WirelessModels::base_wsdaBase_104_usb, WirelessTypes::region_usa); + features = BaseStationFeatures::create(info); + MOCK_EXPECT(impl->features).returns(std::ref(*(features.get()))); + + BaseStationConfig c; + c.transmitPower(WirelessTypes::power_10dBm); + + //expect the single eeprom write + expectWrite(impl, BaseStationEepromMap::TX_POWER_LEVEL, Value(valueType_int16, (int16)WirelessTypes::legacyPower_10dBm)); + expectRead(impl, BaseStationEepromMap::FIRMWARE_VER, Value::UINT16((uint16)(3))); + expectRead(impl, BaseStationEepromMap::FIRMWARE_VER2, Value::UINT16((uint16)(2))); + expectCyclePower(impl); + + BOOST_CHECK_NO_THROW(b.applyConfig(c)); +} BOOST_AUTO_TEST_SUITE_END() \ No newline at end of file diff --git a/MSCL_Unit_Tests/Test_BaseStationEepromHelper.cpp b/MSCL_Unit_Tests/Test_BaseStationEepromHelper.cpp index 1da83115c..985588891 100644 --- a/MSCL_Unit_Tests/Test_BaseStationEepromHelper.cpp +++ b/MSCL_Unit_Tests/Test_BaseStationEepromHelper.cpp @@ -27,23 +27,67 @@ BOOST_AUTO_TEST_CASE(BaseStationEepromHelper_readTransmitPower) std::shared_ptr impl(new mock_baseStationImpl()); BaseStation base(impl); - expectRead(impl, BaseStationEepromMap::TX_POWER_LEVEL, Value::UINT16(WirelessTypes::power_10dBm)); + //make the features() function return the BaseStationFeatures we want + std::unique_ptr features; + expectBaseFeatures(features, impl); + + expectRead(impl, BaseStationEepromMap::TX_POWER_LEVEL, Value(valueType_int16, (int16)WirelessTypes::power_10dBm)); BaseStationEepromHelper c(base.eepromHelper()); BOOST_CHECK_EQUAL(c.read_transmitPower(), WirelessTypes::power_10dBm); } +BOOST_AUTO_TEST_CASE(BaseStationEepromHelper_readTransmitPower_legacy) +{ + std::shared_ptr impl(new mock_baseStationImpl()); + BaseStation base(impl); + + //make the features() function return the BaseStationFeatures we want + std::unique_ptr features; + //3.2 fw doesn't support the new transmit power values + BaseStationInfo info(Version(3, 2), WirelessModels::base_wsdaBase_104_usb, WirelessTypes::region_usa); + features = BaseStationFeatures::create(info); + MOCK_EXPECT(impl->features).returns(std::ref(*(features.get()))); + + expectRead(impl, BaseStationEepromMap::TX_POWER_LEVEL, Value(valueType_int16, (int16)WirelessTypes::legacyPower_0dBm)); + + BaseStationEepromHelper c(base.eepromHelper()); + + BOOST_CHECK_EQUAL(c.read_transmitPower(), WirelessTypes::power_0dBm); +} + BOOST_AUTO_TEST_CASE(BaseStationEepromHelper_writeTransmitPower) { std::shared_ptr impl(new mock_baseStationImpl()); BaseStation base(impl); - expectWrite(impl, BaseStationEepromMap::TX_POWER_LEVEL, Value::UINT16(WirelessTypes::power_16dBm)); + //make the features() function return the BaseStationFeatures we want + std::unique_ptr features; + expectBaseFeatures(features, impl); + + expectWrite(impl, BaseStationEepromMap::TX_POWER_LEVEL, Value(valueType_int16, (int16)WirelessTypes::power_16dBm)); BOOST_CHECK_NO_THROW(base.eepromHelper().write_transmitPower(WirelessTypes::power_16dBm)); } +BOOST_AUTO_TEST_CASE(BaseStationEepromHelper_writeTransmitPower_legacy) +{ + std::shared_ptr impl(new mock_baseStationImpl()); + BaseStation base(impl); + + //make the features() function return the BaseStationFeatures we want + std::unique_ptr features; + //3.2 fw doesn't support the new transmit power values + BaseStationInfo info(Version(3, 2), WirelessModels::base_wsdaBase_104_usb, WirelessTypes::region_usa); + features = BaseStationFeatures::create(info); + MOCK_EXPECT(impl->features).returns(std::ref(*(features.get()))); + + expectWrite(impl, BaseStationEepromMap::TX_POWER_LEVEL, Value(valueType_int16, (int16)WirelessTypes::legacyPower_10dBm)); + + BOOST_CHECK_NO_THROW(base.eepromHelper().write_transmitPower(WirelessTypes::power_10dBm)); +} + BOOST_AUTO_TEST_CASE(BaseStationEepromHelper_readButton) { std::shared_ptr impl(new mock_baseStationImpl()); diff --git a/MSCL_Unit_Tests/Test_ChannelGroup.cpp b/MSCL_Unit_Tests/Test_ChannelGroup.cpp new file mode 100644 index 000000000..71d99acad --- /dev/null +++ b/MSCL_Unit_Tests/Test_ChannelGroup.cpp @@ -0,0 +1,157 @@ +/***************************************************************************** +Copyright(c) 2015 LORD Corporation. All rights reserved. + +This program is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +This program is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the included +LICENSE.txt file for a copy of the full GNU General Public License. +*****************************************************************************/ +#include "mscl/MicroStrain/Wireless/WirelessNode.h" +#include "mscl/MicroStrain/Wireless/BaseStation.h" +#include "mscl/Utils.h" +#include "mscl/MicroStrain/Wireless/Features/NodeFeatures.h" +#include "mscl/MicroStrain/Wireless/Configuration/WirelessNodeConfig.h" +#include "mscl/MicroStrain/Wireless/Configuration/EepromLocation.h" +#include "mscl/MicroStrain/Wireless/Features/ChannelGroup.h" + +#include +#include "mock_BaseStation.h" +#include "mock_WirelessNode.h" +using namespace mscl; + + +BOOST_AUTO_TEST_SUITE(ChannelGroup_Test) + +NodeInfo createInfo(WirelessModels::NodeModel node) +{ + return NodeInfo(Version(9, 9), node, 0, WirelessTypes::region_usa); +} + +BOOST_AUTO_TEST_CASE(ChannelGroup_channelGroups) +{ + std::shared_ptr sglink = NodeFeatures::create(createInfo(WirelessModels::node_sgLink)); + mscl::ChannelGroups groups = sglink->channelGroups(); + + BOOST_CHECK_EQUAL(groups.size(), 4); + BOOST_CHECK_EQUAL(groups.at(0).channels().toMask(), 1); //differential channels + auto diffSettings = groups.at(0).settings(); + BOOST_CHECK_EQUAL(diffSettings.size(), 3); + BOOST_CHECK_EQUAL(diffSettings.at(0), WirelessTypes::chSetting_hardwareGain); + BOOST_CHECK_EQUAL(diffSettings.at(1), WirelessTypes::chSetting_hardwareOffset); + BOOST_CHECK_EQUAL(diffSettings.at(2), WirelessTypes::chSetting_autoBalance); + + BOOST_CHECK_EQUAL(groups.at(1).channels().toMask(), 1); //cal coefficient ch1 + auto ch1Settings = groups.at(1).settings(); + BOOST_CHECK_EQUAL(ch1Settings.at(0), WirelessTypes::chSetting_linearEquation); + BOOST_CHECK_EQUAL(ch1Settings.at(1), WirelessTypes::chSetting_unit); + BOOST_CHECK_EQUAL(ch1Settings.at(2), WirelessTypes::chSetting_equationType); + + BOOST_CHECK_EQUAL(groups.at(2).channels().toMask(), 4); //cal coefficient ch3 + auto ch3Settings = groups.at(2).settings(); + BOOST_CHECK_EQUAL(ch3Settings.at(0), WirelessTypes::chSetting_linearEquation); + BOOST_CHECK_EQUAL(ch3Settings.at(1), WirelessTypes::chSetting_unit); + BOOST_CHECK_EQUAL(ch3Settings.at(2), WirelessTypes::chSetting_equationType); + + BOOST_CHECK_EQUAL(groups.at(3).channels().toMask(), 8); //cal coefficient ch4 + auto ch4Settings = groups.at(3).settings(); + BOOST_CHECK_EQUAL(ch4Settings.at(0), WirelessTypes::chSetting_linearEquation); + BOOST_CHECK_EQUAL(ch4Settings.at(1), WirelessTypes::chSetting_unit); + BOOST_CHECK_EQUAL(ch4Settings.at(2), WirelessTypes::chSetting_equationType); +} + +BOOST_AUTO_TEST_CASE(ChannelGroup_getGaugeFactor) +{ + std::shared_ptr impl(new mock_WirelessNodeImpl(100)); + BaseStation b = makeBaseStationWithMockImpl(); + WirelessNode node(100, b); + node.setImpl(impl); + + NodeInfo info(Version(10, 0), WirelessModels::node_shmLink2, 0, WirelessTypes::region_usa); + + //make the features() function return the NodeFeatures we want + std::unique_ptr features = NodeFeatures::create(info); + expectNodeFeatures(features, impl, WirelessModels::node_shmLink2); + + expectRead(impl, NodeEepromMap::GAUGE_FACTOR_1, Value::FLOAT(1.2345f)); + expectRead(impl, NodeEepromMap::GAUGE_FACTOR_2, Value::FLOAT(713.45101f)); + expectRead(impl, NodeEepromMap::GAUGE_FACTOR_3, Value::FLOAT(0.000152f)); + + BOOST_CHECK_THROW(node.getGaugeFactor(ChannelMask(8)), Error_NotSupported); //ch4 not supported + BOOST_CHECK_CLOSE(node.getGaugeFactor(ChannelMask(1)), 1.2345, 0.001); //ch1 + BOOST_CHECK_CLOSE(node.getGaugeFactor(ChannelMask(2)), 713.45101, 0.001); //ch2 + BOOST_CHECK_CLOSE(node.getGaugeFactor(ChannelMask(4)), 0.000152, 0.001); //ch3 +} + +BOOST_AUTO_TEST_CASE(WirelessNode_getLinearEquation) +{ + std::shared_ptr impl(new mock_WirelessNodeImpl(100)); + BaseStation b = makeBaseStationWithMockImpl(); + WirelessNode node(100, b); + node.setImpl(impl); + + NodeInfo info(Version(9, 9), WirelessModels::node_gLink_2g, 0, WirelessTypes::region_usa); + + //make the features() function return the NodeFeatures we want + std::unique_ptr features = NodeFeatures::create(info); + expectNodeFeatures(features, impl, WirelessModels::node_gLink_2g); + + //reading channel 1 + expectRead(impl, NodeEepromMap::CH_ACTION_SLOPE_1, Value::FLOAT(12.789f)); //slope + expectRead(impl, NodeEepromMap::CH_ACTION_OFFSET_1, Value::FLOAT(-48.001f)); //offset + expectRead(impl, NodeEepromMap::CH_ACTION_SLOPE_3, Value::FLOAT(6.45f)); //slope + expectRead(impl, NodeEepromMap::CH_ACTION_OFFSET_3, Value::FLOAT(-0.002f)); //offset + expectRead(impl, NodeEepromMap::CH_ACTION_ID_1, Value::UINT16(static_cast(0x0407))); //equation and unit + + LinearEquation eq = node.getLinearEquation(ChannelMask(1));//ch1 + LinearEquation eq2 = node.getLinearEquation(ChannelMask(4));//ch3 + + BOOST_CHECK_CLOSE(eq.slope(), 12.789, 0.1); + BOOST_CHECK_CLOSE(eq.offset(), -48.001, 0.1); + BOOST_CHECK_CLOSE(eq2.slope(), 6.45, 0.1); + BOOST_CHECK_CLOSE(eq2.offset(), -0.002, 0.1); + BOOST_CHECK_EQUAL(node.getUnit(ChannelMask(1)), WirelessTypes::unit_volts_millivolts); + BOOST_CHECK_EQUAL(node.getEquationType(ChannelMask(1)), WirelessTypes::equation_standard); +} + +BOOST_AUTO_TEST_CASE(ChannelGroup_getThermocoupleType) +{ + //tests get thermocouple fail (not supported) + { + std::shared_ptr impl(new mock_WirelessNodeImpl(100)); + BaseStation b = makeBaseStationWithMockImpl(); + WirelessNode node(100, b); + node.setImpl(impl); + + NodeInfo info(Version(9, 9), WirelessModels::node_gLink_2g, 0, WirelessTypes::region_usa); + + //make the features() function return the NodeFeatures we want + std::unique_ptr features = NodeFeatures::create(info); + expectNodeFeatures(features, impl, WirelessModels::node_gLink_2g); + + BOOST_CHECK_THROW(node.getThermocoupleType(ChannelMask(1)), Error_NotSupported); + } + + //tests get thermocouple success + { + std::shared_ptr impl(new mock_WirelessNodeImpl(100)); + BaseStation b = makeBaseStationWithMockImpl(); + WirelessNode node(100, b); + node.setImpl(impl); + + std::unique_ptr features; + expectNodeFeatures(features, impl, WirelessModels::node_tcLink_3ch); + + expectRead(impl, NodeEepromMap::THERMOCPL_TYPE, Value::UINT16(WirelessTypes::tc_N)); + + BOOST_CHECK_EQUAL(node.getThermocoupleType(ChannelMask(BOOST_BINARY(00000111))), WirelessTypes::tc_N); + BOOST_CHECK_THROW(node.getThermocoupleType(ChannelMask(BOOST_BINARY(00000101))), Error_NotSupported); + BOOST_CHECK_THROW(node.getThermocoupleType(ChannelMask(BOOST_BINARY(00000001))), Error_NotSupported); + } +} + +BOOST_AUTO_TEST_SUITE_END() \ No newline at end of file diff --git a/MSCL_Unit_Tests/Test_EstFilterCommands.cpp b/MSCL_Unit_Tests/Test_EstFilterCommands.cpp index 55cc504b8..87b97e5c7 100644 --- a/MSCL_Unit_Tests/Test_EstFilterCommands.cpp +++ b/MSCL_Unit_Tests/Test_EstFilterCommands.cpp @@ -14,6 +14,8 @@ LICENSE.txt file for a copy of the full GNU General Public License. #include "mscl/MicroStrain/Inertial/Commands/EstFilter_Commands.h" #include "mscl/MicroStrain/Inertial/InertialDataField.h" #include "mscl/MicroStrain/ResponseCollector.h" +#include "mscl/MicroStrain/Inertial/EulerAngles.h" +#include "mscl/MicroStrain/Inertial/PositionOffset.h" #include using namespace mscl; @@ -45,7 +47,7 @@ BOOST_AUTO_TEST_CASE(GetEstFilterDataRateBase_parseData) std::shared_ptr rc(new ResponseCollector); GetEstFilterDataRateBase::Response response(rc); - BOOST_CHECK_EQUAL(response.parseData(GenericInertialCommandResponse::ResponseSuccess("", data)), 500); + BOOST_CHECK_EQUAL(response.parseResponse(GenericInertialCommandResponse::ResponseSuccess("", data)), 500); } BOOST_AUTO_TEST_CASE(GetEstFilterDataRateBase_Match_Success) @@ -135,7 +137,7 @@ BOOST_AUTO_TEST_CASE(EstFilterMessageFormat_parseData) uint16 sampleRateBase = 100; - InertialChannels chs = response.parseData(GenericInertialCommandResponse::ResponseSuccess("", data), sampleRateBase); + InertialChannels chs = response.parseResponse(GenericInertialCommandResponse::ResponseSuccess("", data), sampleRateBase); BOOST_CHECK_EQUAL(chs.size(), 1); BOOST_CHECK_EQUAL(chs.at(0).channelField(), InertialTypes::CH_FIELD_ESTFILTER_ESTIMATED_GYRO_BIAS); @@ -146,5 +148,140 @@ BOOST_AUTO_TEST_CASE(EstFilterMessageFormat_parseData) BOOST_AUTO_TEST_SUITE_END() //End EstFilterMessageFormat +BOOST_AUTO_TEST_SUITE(EstFilterCommands_SensorToVehicFrameTrans) + +BOOST_AUTO_TEST_CASE(SensorToVehicFrameTrans_buildCommand_get) +{ + ByteStream b = SensorToVehicFrameTrans::buildCommand_get(); + + //Check all the bytes in the ByteStream + BOOST_CHECK_EQUAL(b.read_uint8(0), 0x75); + BOOST_CHECK_EQUAL(b.read_uint8(1), 0x65); + BOOST_CHECK_EQUAL(b.read_uint8(2), 0x0D); + BOOST_CHECK_EQUAL(b.read_uint8(3), 0x03); //payload len + BOOST_CHECK_EQUAL(b.read_uint8(4), 0x03); //field len + BOOST_CHECK_EQUAL(b.read_uint8(5), 0x11); //field desc + BOOST_CHECK_EQUAL(b.read_uint8(6), 0x02); + BOOST_CHECK_EQUAL(b.read_uint8(7), 0x00); + BOOST_CHECK_EQUAL(b.read_uint8(8), 0x0B); +} + +BOOST_AUTO_TEST_CASE(SensorToVehicFrameTrans_buildCommand_set) +{ + mscl::EulerAngles angles(1.5f, 10.123f, 0.018945f); + + ByteStream b = SensorToVehicFrameTrans::buildCommand_set(angles); + + //Check all the bytes in the ByteStream + BOOST_CHECK_EQUAL(b.read_uint8(0), 0x75); + BOOST_CHECK_EQUAL(b.read_uint8(1), 0x65); + BOOST_CHECK_EQUAL(b.read_uint8(2), 0x0D); + BOOST_CHECK_EQUAL(b.read_uint8(3), 0x0F); //payload len + BOOST_CHECK_EQUAL(b.read_uint8(4), 0x0F); //field len + BOOST_CHECK_EQUAL(b.read_uint8(5), 0x11); //field desc + BOOST_CHECK_EQUAL(b.read_uint8(6), 0x01); + BOOST_CHECK_EQUAL(b.read_uint8(7), 0x3F); + BOOST_CHECK_EQUAL(b.read_uint8(8), 0xC0); + BOOST_CHECK_EQUAL(b.read_uint8(9), 0x00); + BOOST_CHECK_EQUAL(b.read_uint8(10), 0x00); + BOOST_CHECK_EQUAL(b.read_uint8(11), 0x41); + BOOST_CHECK_EQUAL(b.read_uint8(12), 0x21); + BOOST_CHECK_EQUAL(b.read_uint8(13), 0xF7); + BOOST_CHECK_EQUAL(b.read_uint8(14), 0xCF); + BOOST_CHECK_EQUAL(b.read_uint8(15), 0x3C); + BOOST_CHECK_EQUAL(b.read_uint8(16), 0x9B); + BOOST_CHECK_EQUAL(b.read_uint8(17), 0x32); + BOOST_CHECK_EQUAL(b.read_uint8(18), 0x8B); + BOOST_CHECK_EQUAL(b.read_uint8(19), 0xD2); + BOOST_CHECK_EQUAL(b.read_uint8(20), 0x1A); +} + +BOOST_AUTO_TEST_CASE(SensorToVehicFrameTrans_parseData) +{ + ByteStream data; + data.append_float(-2.3f); + data.append_float(0.34234f); + data.append_float(0.00019f); + + std::shared_ptr rc(new ResponseCollector); + SensorToVehicFrameTrans::Response response(rc, true); + + mscl::EulerAngles angles = response.parseResponse(GenericInertialCommandResponse::ResponseSuccess("", data)); + + BOOST_CHECK_CLOSE(angles.roll(), -2.3, 0.001); + BOOST_CHECK_CLOSE(angles.pitch(), 0.34234, 0.001); + BOOST_CHECK_CLOSE(angles.yaw(), 0.00019, 0.001); +} + +BOOST_AUTO_TEST_SUITE_END() //End EstFilterCommands_SensorToVehicFrameTrans + + +BOOST_AUTO_TEST_SUITE(EstFilterCommands_SensorToVehicFrameOffset) + +BOOST_AUTO_TEST_CASE(SensorToVehicFrameOffset_buildCommand_get) +{ + ByteStream b = SensorToVehicFrameOffset::buildCommand_get(); + + //Check all the bytes in the ByteStream + BOOST_CHECK_EQUAL(b.read_uint8(0), 0x75); + BOOST_CHECK_EQUAL(b.read_uint8(1), 0x65); + BOOST_CHECK_EQUAL(b.read_uint8(2), 0x0D); + BOOST_CHECK_EQUAL(b.read_uint8(3), 0x03); //payload len + BOOST_CHECK_EQUAL(b.read_uint8(4), 0x03); //field len + BOOST_CHECK_EQUAL(b.read_uint8(5), 0x12); //field desc + BOOST_CHECK_EQUAL(b.read_uint8(6), 0x02); + BOOST_CHECK_EQUAL(b.read_uint8(7), 0x01); + BOOST_CHECK_EQUAL(b.read_uint8(8), 0x0D); +} + +BOOST_AUTO_TEST_CASE(SensorToVehicFrameOffset_buildCommand_set) +{ + mscl::PositionOffset offset(1.5f, -1.123f, 0.018945f); + + ByteStream b = SensorToVehicFrameOffset::buildCommand_set(offset); + + //Check all the bytes in the ByteStream + BOOST_CHECK_EQUAL(b.read_uint8(0), 0x75); + BOOST_CHECK_EQUAL(b.read_uint8(1), 0x65); + BOOST_CHECK_EQUAL(b.read_uint8(2), 0x0D); + BOOST_CHECK_EQUAL(b.read_uint8(3), 0x0F); //payload len + BOOST_CHECK_EQUAL(b.read_uint8(4), 0x0F); //field len + BOOST_CHECK_EQUAL(b.read_uint8(5), 0x12); //field desc + BOOST_CHECK_EQUAL(b.read_uint8(6), 0x01); + BOOST_CHECK_EQUAL(b.read_uint8(7), 0x3F); + BOOST_CHECK_EQUAL(b.read_uint8(8), 0xC0); + BOOST_CHECK_EQUAL(b.read_uint8(9), 0x00); + BOOST_CHECK_EQUAL(b.read_uint8(10), 0x00); + BOOST_CHECK_EQUAL(b.read_uint8(11), 0xBF); + BOOST_CHECK_EQUAL(b.read_uint8(12), 0x8F); + BOOST_CHECK_EQUAL(b.read_uint8(13), 0xBE); + BOOST_CHECK_EQUAL(b.read_uint8(14), 0x77); + BOOST_CHECK_EQUAL(b.read_uint8(15), 0x3C); + BOOST_CHECK_EQUAL(b.read_uint8(16), 0x9B); + BOOST_CHECK_EQUAL(b.read_uint8(17), 0x32); + BOOST_CHECK_EQUAL(b.read_uint8(18), 0x8B); + BOOST_CHECK_EQUAL(b.read_uint8(19), 0x2E); + BOOST_CHECK_EQUAL(b.read_uint8(20), 0x0C); +} + +BOOST_AUTO_TEST_CASE(SensorToVehicFrameOffset_parseData) +{ + ByteStream data; + data.append_float(-5.3f); + data.append_float(0.3234f); + data.append_float(0.70019f); + + std::shared_ptr rc(new ResponseCollector); + SensorToVehicFrameOffset::Response response(rc, true); + + mscl::PositionOffset offset = response.parseResponse(GenericInertialCommandResponse::ResponseSuccess("", data)); + + BOOST_CHECK_CLOSE(offset.x(), -5.3, 0.001); + BOOST_CHECK_CLOSE(offset.y(), 0.3234, 0.001); + BOOST_CHECK_CLOSE(offset.z(), 0.70019, 0.001); +} + +BOOST_AUTO_TEST_SUITE_END() //End EstFilterCommands_SensorToVehicFrameTrans + BOOST_AUTO_TEST_SUITE_END() \ No newline at end of file diff --git a/MSCL_Unit_Tests/Test_GetDeviceInfo.cpp b/MSCL_Unit_Tests/Test_GetDeviceInfo.cpp index ff5298aed..ef1aa3217 100644 --- a/MSCL_Unit_Tests/Test_GetDeviceInfo.cpp +++ b/MSCL_Unit_Tests/Test_GetDeviceInfo.cpp @@ -205,7 +205,7 @@ BOOST_AUTO_TEST_CASE(GetDeviceInfo_Match_Success) BOOST_CHECK_EQUAL(response.result().success(), true); BOOST_CHECK_EQUAL(response.result().errorCode(), mscl::InertialPacket::MIP_ACK_NACK_ERROR_NONE); - mscl::InertialDeviceInfo resultInfo = response.parseData(response.result()); + mscl::InertialDeviceInfo resultInfo = response.parseResponse(response.result()); BOOST_CHECK_EQUAL(resultInfo.fwVersion.str(), "1.1.17"); } diff --git a/MSCL_Unit_Tests/Test_GpsCommands.cpp b/MSCL_Unit_Tests/Test_GpsCommands.cpp index 7e4ae8b45..e00f1fbe3 100644 --- a/MSCL_Unit_Tests/Test_GpsCommands.cpp +++ b/MSCL_Unit_Tests/Test_GpsCommands.cpp @@ -45,7 +45,7 @@ BOOST_AUTO_TEST_CASE(GetGpsDataRateBase_parseData) std::shared_ptr rc(new ResponseCollector); GetGpsDataRateBase::Response response(rc); - BOOST_CHECK_EQUAL(response.parseData(GenericInertialCommandResponse::ResponseSuccess("", data)), 1000); + BOOST_CHECK_EQUAL(response.parseResponse(GenericInertialCommandResponse::ResponseSuccess("", data)), 1000); } BOOST_AUTO_TEST_CASE(GetGpsDataRateBase_Match_Success) @@ -133,7 +133,7 @@ BOOST_AUTO_TEST_CASE(GpsMessageFormat_parseData) uint16 sampleRateBase = 1000; - InertialChannels chs = response.parseData(GenericInertialCommandResponse::ResponseSuccess("", data), sampleRateBase); + InertialChannels chs = response.parseResponse(GenericInertialCommandResponse::ResponseSuccess("", data), sampleRateBase); BOOST_CHECK_EQUAL(chs.size(), 1); BOOST_CHECK_EQUAL(chs.at(0).channelField(), InertialTypes::CH_FIELD_GPS_UTC_TIME); diff --git a/MSCL_Unit_Tests/Test_NodeFeatures.cpp b/MSCL_Unit_Tests/Test_NodeFeatures.cpp index 905de0397..2d1ddcbea 100644 --- a/MSCL_Unit_Tests/Test_NodeFeatures.cpp +++ b/MSCL_Unit_Tests/Test_NodeFeatures.cpp @@ -91,6 +91,15 @@ BOOST_AUTO_TEST_CASE(NodeFeatures_create_unknownModel) BOOST_CHECK_THROW(NodeFeatures::create(createInfo(static_cast(0))), Error_NotSupported); } +BOOST_AUTO_TEST_CASE(NodeFeatures_supportsGaugeFactor) +{ + std::shared_ptr sglink = NodeFeatures::create(createInfo(WirelessModels::node_sgLink)); + BOOST_CHECK_EQUAL(sglink->supportsGaugeFactor(), false); + + std::shared_ptr shmLink2 = NodeFeatures::create(createInfo(WirelessModels::node_shmLink2)); + BOOST_CHECK_EQUAL(shmLink2->supportsGaugeFactor(), true); +} + BOOST_AUTO_TEST_CASE(NodeFeatures_supportsDefaultMode) { std::shared_ptr glink = NodeFeatures::create(createInfo(WirelessModels::node_gLink_10g)); diff --git a/MSCL_Unit_Tests/Test_SensorCommands.cpp b/MSCL_Unit_Tests/Test_SensorCommands.cpp index f29388f1d..479e1b4e6 100644 --- a/MSCL_Unit_Tests/Test_SensorCommands.cpp +++ b/MSCL_Unit_Tests/Test_SensorCommands.cpp @@ -45,7 +45,7 @@ BOOST_AUTO_TEST_CASE(GetSensorDataRateBase_parseData) std::shared_ptr rc(new ResponseCollector); GetSensorDataRateBase::Response response(rc); - BOOST_CHECK_EQUAL(response.parseData(GenericInertialCommandResponse::ResponseSuccess("", data)), 4000); + BOOST_CHECK_EQUAL(response.parseResponse(GenericInertialCommandResponse::ResponseSuccess("", data)), 4000); } BOOST_AUTO_TEST_CASE(GetSensorDataRateBase_Match_Success) @@ -137,7 +137,7 @@ BOOST_AUTO_TEST_CASE(SensorMessageFormat_parseData) uint16 sampleRateBase = 50; - InertialChannels chs = response.parseData(GenericInertialCommandResponse::ResponseSuccess("", data), sampleRateBase); + InertialChannels chs = response.parseResponse(GenericInertialCommandResponse::ResponseSuccess("", data), sampleRateBase); BOOST_CHECK_EQUAL(chs.size(), 2); BOOST_CHECK_EQUAL(chs.at(0).channelField(), InertialTypes::CH_FIELD_SENSOR_SCALED_MAG_VEC); diff --git a/MSCL_Unit_Tests/Test_SerialConnection.cpp b/MSCL_Unit_Tests/Test_SerialConnection.cpp index 6fb6c59d5..f5b02f973 100644 --- a/MSCL_Unit_Tests/Test_SerialConnection.cpp +++ b/MSCL_Unit_Tests/Test_SerialConnection.cpp @@ -26,7 +26,7 @@ LICENSE.txt file for a copy of the full GNU General Public License. using namespace mscl; -void parseData(DataBuffer& data) +void parseResponse(DataBuffer& data) { } diff --git a/MSCL_Unit_Tests/Test_WirelessNode.cpp b/MSCL_Unit_Tests/Test_WirelessNode.cpp index 2b7343baf..06e7383c3 100644 --- a/MSCL_Unit_Tests/Test_WirelessNode.cpp +++ b/MSCL_Unit_Tests/Test_WirelessNode.cpp @@ -286,7 +286,7 @@ BOOST_AUTO_TEST_CASE(WirelessNode_cyclePower) WirelessNode node(123, b); node.setImpl(impl); - expectWrite(impl, NodeEepromMap::CYCLE_POWER, Value::UINT16(1)); + expectCyclePower(impl); BOOST_CHECK_NO_THROW(node.cyclePower()); } @@ -297,13 +297,13 @@ BOOST_AUTO_TEST_CASE(WirelessNode_frequency) BaseStation base(impl); //call the create function - WirelessNode node(123, base, WirelessTypes::freq_16); + WirelessNode node(123, base); //force the page download to fail MOCK_EXPECT(impl->node_pageDownload).returns(false); MOCK_EXPECT(impl->node_readEeprom).once().with(mock::any, mock::any, 108, mock::assign(1)).returns(true); + MOCK_EXPECT(impl->node_readEeprom).once().with(mock::any, mock::any, 90, mock::assign(16)).returns(true); - //check the frequency is what we set in the create function BOOST_CHECK_EQUAL(node.frequency(), WirelessTypes::freq_16); MOCK_EXPECT(impl->node_writeEeprom).once().with(mock::any, 123, 90, mock::any).returns(true); //change frequency write @@ -317,9 +317,6 @@ BOOST_AUTO_TEST_CASE(WirelessNode_frequency) //try to change again, but fail MOCK_EXPECT(impl->node_writeEeprom).once().with(mock::any, 123, 90, mock::any).returns(false); //change frequency write BOOST_CHECK_THROW(node.changeFrequency(WirelessTypes::freq_12), Error_NodeCommunication); - - //check that nothing has changed - BOOST_CHECK_EQUAL(node.frequency(), WirelessTypes::freq_18); } BOOST_AUTO_TEST_CASE(WirelessNode_get_and_setBaseStation) @@ -329,7 +326,7 @@ BOOST_AUTO_TEST_CASE(WirelessNode_get_and_setBaseStation) base.baseCommandsTimeout(30000); //change the timeout to 30 seconds //call the create function - WirelessNode node(123, base, WirelessTypes::freq_16); + WirelessNode node(123, base); BOOST_CHECK(node.getBaseStation().baseCommandsTimeout() == 30000); @@ -449,7 +446,7 @@ BOOST_AUTO_TEST_CASE(NodeConfig_setBootMode) expectNodeFeatures(features, impl); expectWrite(impl, NodeEepromMap::DEFAULT_MODE, Value::UINT16(6)); - expectResetRadio(impl); + expectCyclePower(impl); WirelessNodeConfig c; c.defaultMode(WirelessTypes::defaultMode_sync); @@ -483,7 +480,7 @@ BOOST_AUTO_TEST_CASE(NodeConfig_setInactivityTimeout) expectNodeFeatures(features, impl); expectWrite(impl, NodeEepromMap::INACTIVE_TIMEOUT, Value::UINT16(5)); //min of 5 - expectResetRadio(impl); + expectCyclePower(impl); uint16 timeout = 2; Utils::checkBounds_min(timeout, features->minInactivityTimeout()); @@ -494,7 +491,7 @@ BOOST_AUTO_TEST_CASE(NodeConfig_setInactivityTimeout) BOOST_CHECK_NO_THROW(node.applyConfig(c)); expectWrite(impl, NodeEepromMap::INACTIVE_TIMEOUT, Value::UINT16(400)); - expectResetRadio(impl); + expectCyclePower(impl); c.inactivityTimeout(400); @@ -541,8 +538,8 @@ BOOST_AUTO_TEST_CASE(NodeConfig_setTransmitPower) std::unique_ptr features; expectNodeFeatures(features, impl); - expectWrite(impl, NodeEepromMap::TX_POWER_LEVEL, Value::UINT16(25619)); - expectResetRadio(impl); + expectWrite(impl, NodeEepromMap::TX_POWER_LEVEL, Value(valueType_int16, (int16)25619)); + expectCyclePower(impl); WirelessNodeConfig c; c.transmitPower(WirelessTypes::power_16dBm); @@ -592,73 +589,6 @@ BOOST_AUTO_TEST_CASE(NodeConfig_getLostBeconTimeout) } } -BOOST_AUTO_TEST_CASE(WirelessNode_getThermocoupleType) -{ - //tests get thermocouple fail (not supported) - { - std::shared_ptr impl(new mock_WirelessNodeImpl(100)); - BaseStation b = makeBaseStationWithMockImpl(); - WirelessNode node(100, b); - node.setImpl(impl); - - NodeInfo info(Version(9, 9), WirelessModels::node_gLink_2g, 0, WirelessTypes::region_usa); - - //make the features() function return the NodeFeatures we want - std::unique_ptr features = NodeFeatures::create(info); - expectNodeFeatures(features, impl, WirelessModels::node_gLink_2g); - - BOOST_CHECK_THROW(node.getThermocoupleType(ChannelMask(1)), Error_NotSupported); - } - - //tests get thermocouple success - { - std::shared_ptr impl(new mock_WirelessNodeImpl(100)); - BaseStation b = makeBaseStationWithMockImpl(); - WirelessNode node(100, b); - node.setImpl(impl); - - std::unique_ptr features; - expectNodeFeatures(features, impl, WirelessModels::node_tcLink_3ch); - - expectRead(impl, NodeEepromMap::THERMOCPL_TYPE, Value::UINT16(WirelessTypes::tc_N)); - - BOOST_CHECK_EQUAL(node.getThermocoupleType(ChannelMask(BOOST_BINARY(00000111))), WirelessTypes::tc_N); - BOOST_CHECK_THROW(node.getThermocoupleType(ChannelMask(BOOST_BINARY(00000101))), Error_NotSupported); - BOOST_CHECK_THROW(node.getThermocoupleType(ChannelMask(BOOST_BINARY(00000001))), Error_NotSupported); - } -} - -BOOST_AUTO_TEST_CASE(WirelessNode_getLinearEquation) -{ - std::shared_ptr impl(new mock_WirelessNodeImpl(100)); - BaseStation b = makeBaseStationWithMockImpl(); - WirelessNode node(100, b); - node.setImpl(impl); - - NodeInfo info(Version(9, 9), WirelessModels::node_gLink_2g, 0, WirelessTypes::region_usa); - - //make the features() function return the NodeFeatures we want - std::unique_ptr features = NodeFeatures::create(info); - expectNodeFeatures(features, impl, WirelessModels::node_gLink_2g); - - //reading channel 1 - expectRead(impl, NodeEepromMap::CH_ACTION_SLOPE_1, Value::FLOAT(12.789f)); //slope - expectRead(impl, NodeEepromMap::CH_ACTION_OFFSET_1, Value::FLOAT(-48.001f)); //offset - expectRead(impl, NodeEepromMap::CH_ACTION_SLOPE_3, Value::FLOAT(6.45f)); //slope - expectRead(impl, NodeEepromMap::CH_ACTION_OFFSET_3, Value::FLOAT(-0.002f)); //offset - expectRead(impl, NodeEepromMap::CH_ACTION_ID_1, Value::UINT16(static_cast(0x0407))); //equation and unit - - LinearEquation eq = node.getLinearEquation(ChannelMask(1));//ch1 - LinearEquation eq2 = node.getLinearEquation(ChannelMask(4));//ch3 - - BOOST_CHECK_CLOSE(eq.slope(), 12.789, 0.1); - BOOST_CHECK_CLOSE(eq.offset(), -48.001, 0.1); - BOOST_CHECK_CLOSE(eq2.slope(), 6.45, 0.1); - BOOST_CHECK_CLOSE(eq2.offset(), -0.002, 0.1); - BOOST_CHECK_EQUAL(node.getUnit(ChannelMask(1)), WirelessTypes::unit_volts_millivolts); - BOOST_CHECK_EQUAL(node.getEquationType(ChannelMask(1)), WirelessTypes::equation_standard); -} - BOOST_AUTO_TEST_CASE(WirelessNode_getFatigueOptions_legacy) { std::shared_ptr impl(new mock_WirelessNodeImpl(100)); @@ -713,13 +643,13 @@ BOOST_AUTO_TEST_CASE(WirelessNode_getFatigueOptions) WirelessNode node(100, b); node.setImpl(impl); - NodeInfo info(Version(9, 9), WirelessModels::node_shmLink2, 0, WirelessTypes::region_usa); + NodeInfo info(Version(10, 9), WirelessModels::node_shmLink2, 0, WirelessTypes::region_usa); //make the features() function return the NodeFeatures we want std::unique_ptr features = NodeFeatures::create(info); expectNodeFeatures(features, impl, WirelessModels::node_shmLink2); - expectRead(impl, NodeEepromMap::PEAK_VALLEY_THRES, Value::UINT16(64318)); //peak/valley + expectRead(impl, NodeEepromMap::PEAK_VALLEY_THRES, Value::UINT16(64318)); //peak/valley expectRead(impl, NodeEepromMap::YOUNGS_MODULUS, Value::FLOAT(123.5f)); //youngs modulus expectRead(impl, NodeEepromMap::POISSONS_RATIO, Value::FLOAT(943.12f)); //poissons ratio expectRead(impl, NodeEepromMap::HISTOGRAM_RAW_FLAG, Value::UINT16(1)); //youngs modulus @@ -732,6 +662,11 @@ BOOST_AUTO_TEST_CASE(WirelessNode_getFatigueOptions) expectRead(impl, NodeEepromMap::SNCURVE_M_2, Value::FLOAT(0.9f)); //sn curve segment 2 - m expectRead(impl, NodeEepromMap::SNCURVE_LOGA_3, Value::FLOAT(0.7f)); //sn curve segment 3 - loga expectRead(impl, NodeEepromMap::SNCURVE_M_3, Value::FLOAT(0.002f)); //sn curve segment 3 - m + expectRead(impl, NodeEepromMap::FATIGUE_MODE, Value::UINT16(1)); //fatigue mode + expectRead(impl, NodeEepromMap::DIST_ANGLE_NUM_ANGLES, Value::UINT16(6)); //dist angle mode num angles + expectRead(impl, NodeEepromMap::DIST_ANGLE_LOWER_BOUND, Value::FLOAT(2.456f)); //dist angle mode lower bound + expectRead(impl, NodeEepromMap::DIST_ANGLE_UPPER_BOUND, Value::FLOAT(10.412f)); //dist angle mode upper bound + expectRead(impl, NodeEepromMap::HISTOGRAM_ENABLE, Value::UINT16(1)); //histogram enable auto fatigue = node.getFatigueOptions(); @@ -749,6 +684,11 @@ BOOST_AUTO_TEST_CASE(WirelessNode_getFatigueOptions) BOOST_CHECK_CLOSE(fatigue.snCurveSegment(1).m(), 0.9, 0.1); BOOST_CHECK_CLOSE(fatigue.snCurveSegment(2).logA(), 0.7, 0.1); BOOST_CHECK_CLOSE(fatigue.snCurveSegment(2).m(), 0.002, 0.1); + BOOST_CHECK_EQUAL(fatigue.fatigueMode(), WirelessTypes::fatigueMode_distributedAngle); + BOOST_CHECK_EQUAL(fatigue.distributedAngleMode_numAngles(), 6); + BOOST_CHECK_CLOSE(fatigue.distributedAngleMode_lowerBound(), 2.456, 0.1); + BOOST_CHECK_CLOSE(fatigue.distributedAngleMode_upperBound(), 10.412, 0.1); + BOOST_CHECK_EQUAL(fatigue.histogramEnable(), true); } BOOST_AUTO_TEST_CASE(WirelessNode_getHistogramOptions_legacy) @@ -811,7 +751,7 @@ BOOST_AUTO_TEST_CASE(WirelessNode_clearHistogram) std::unique_ptr features = NodeFeatures::create(info); expectNodeFeatures(features, impl, WirelessModels::node_shmLink2); - expectWrite(impl, NodeEepromMap::CYCLE_POWER, Value::UINT16(1)); + expectCyclePower(impl); expectWrite(impl, NodeEepromMap::RESET_BINS, Value::UINT16(1)); BOOST_CHECK_NO_THROW(node.clearHistogram()); diff --git a/MSCL_Unit_Tests/Test_WirelessNodeConfig.cpp b/MSCL_Unit_Tests/Test_WirelessNodeConfig.cpp index e0377ab61..c1d3b9421 100644 --- a/MSCL_Unit_Tests/Test_WirelessNodeConfig.cpp +++ b/MSCL_Unit_Tests/Test_WirelessNodeConfig.cpp @@ -86,7 +86,7 @@ BOOST_AUTO_TEST_CASE(WirelessNodeConfig_setSingleValue) //expect the single eeprom write expectWrite(impl, NodeEepromMap::INACTIVE_TIMEOUT, Value::UINT16(4500)); - expectResetRadio(impl); + expectCyclePower(impl); BOOST_CHECK_NO_THROW(node.applyConfig(c)); } @@ -101,7 +101,7 @@ BOOST_AUTO_TEST_CASE(WirelessNodeConfig_setMultipleValues) node.setImpl(impl); //make the features() function return the NodeFeatures we want - NodeInfo info(Version(9, 9), WirelessModels::node_gLink_2g, 200000, WirelessTypes::region_usa); + NodeInfo info(Version(99, 9), WirelessModels::node_gLink_2g, 200000, WirelessTypes::region_usa); std::unique_ptr features = NodeFeatures::create(info); MOCK_EXPECT(impl->features).returns(std::ref(*(features.get()))); @@ -111,8 +111,8 @@ BOOST_AUTO_TEST_CASE(WirelessNodeConfig_setMultipleValues) //expect the eeprom writes expectWrite(impl, NodeEepromMap::INACTIVE_TIMEOUT, Value::UINT16(200)); - expectWrite(impl, NodeEepromMap::TX_POWER_LEVEL, Value::UINT16(WirelessTypes::power_16dBm)); - expectResetRadio(impl); + expectWrite(impl, NodeEepromMap::TX_POWER_LEVEL, Value(valueType_int16, (int16)WirelessTypes::power_16dBm)); + expectCyclePower(impl); BOOST_CHECK_NO_THROW(node.applyConfig(c)); } @@ -470,7 +470,7 @@ BOOST_AUTO_TEST_CASE(WirelessNodeConfig_checkRadioInterval) BOOST_CHECK_THROW(node.applyConfig(c), Error_InvalidNodeConfig); expectWrite(impl, NodeEepromMap::SLEEP_INTERVAL, Value::UINT16(284)); - expectResetRadio(impl); + expectCyclePower(impl); c.checkRadioInterval(27); BOOST_CHECK_NO_THROW(node.applyConfig(c)); } @@ -494,7 +494,7 @@ BOOST_AUTO_TEST_CASE(WirelessNodeConfig_lostBeaconTimeout) //check the beacon timeout success c.lostBeaconTimeout(45); expectWrite(impl, NodeEepromMap::LOST_BEACON_TIMEOUT, Value::UINT16(45)); - expectResetRadio(impl); + expectCyclePower(impl); BOOST_CHECK_NO_THROW(node.applyConfig(c)); //check the beacon timeout maximum failing @@ -522,7 +522,7 @@ BOOST_AUTO_TEST_CASE(WirelessNodeConfig_bootMode) expectNodeFeatures(features, impl, WirelessModels::node_gLink_10g); expectWrite(impl, NodeEepromMap::DEFAULT_MODE, Value::UINT16(WirelessTypes::defaultMode_ldc)); - expectResetRadio(impl); + expectCyclePower(impl); BOOST_CHECK_NO_THROW(node.applyConfig(c)); } @@ -604,7 +604,7 @@ BOOST_AUTO_TEST_CASE(WirelessNodeConfig_filterSettlingTime) //expect the single eeprom write expectWrite(impl, NodeEepromMap::FILTER_1, Value::UINT16(3)); - expectResetRadio(impl); + expectCyclePower(impl); //check the settling time succeeds to apply BOOST_CHECK_NO_THROW(node.applyConfig(c)); @@ -656,7 +656,7 @@ BOOST_AUTO_TEST_CASE(WirelessNodeConfig_thermocoupleType) //expect the single eeprom write expectWrite(impl, NodeEepromMap::THERMOCPL_TYPE, Value::UINT16(2)); - expectResetRadio(impl); + expectCyclePower(impl); //check the settling time succeeds to apply BOOST_CHECK_NO_THROW(node.applyConfig(c)); @@ -686,7 +686,7 @@ BOOST_AUTO_TEST_CASE(WirelessNodeConfig_linearEquation) //expect the single eeprom write expectWrite(impl, NodeEepromMap::CH_ACTION_SLOPE_4, Value::FLOAT(64.78f)); expectWrite(impl, NodeEepromMap::CH_ACTION_OFFSET_4, Value::FLOAT(142.23f)); - expectResetRadio(impl); + expectCyclePower(impl); BOOST_CHECK_NO_THROW(node.applyConfig(c)); @@ -695,4 +695,63 @@ BOOST_AUTO_TEST_CASE(WirelessNodeConfig_linearEquation) BOOST_CHECK_EQUAL(node.verifyConfig(c, issues), true); } +BOOST_AUTO_TEST_CASE(WirelessNodeConfig_verify_fatigueDistAngles) +{ + std::shared_ptr impl(new mock_WirelessNodeImpl()); + BaseStation b = makeBaseStationWithMockImpl(); + WirelessNode node(123, b); + node.setImpl(impl); + + std::unique_ptr features; + expectNodeFeatures(features, impl, WirelessModels::node_shmLink2_cust1); + + //test good angle settings + FatigueOptions opts; + opts.distributedAngleMode_lowerBound(5.0f); + opts.distributedAngleMode_upperBound(320.4513f); + opts.distributedAngleMode_numAngles(16); + + WirelessNodeConfig c; + c.fatigueOptions(opts); + + ConfigIssues issues; + BOOST_CHECK_EQUAL(node.verifyConfig(c, issues), true); + + //test good very large angle + opts.distributedAngleMode_lowerBound(0.4f); + opts.distributedAngleMode_upperBound(359.5f); + c.fatigueOptions(opts); + BOOST_CHECK_EQUAL(node.verifyConfig(c, issues), true); + + //test bad wrap around angle (too close) + opts.distributedAngleMode_lowerBound(359.5f); + opts.distributedAngleMode_upperBound(.3f); + c.fatigueOptions(opts); + BOOST_CHECK_EQUAL(node.verifyConfig(c, issues), false); + BOOST_CHECK_EQUAL(issues.at(0).id(), ConfigIssue::CONFIG_FATIGUE_DIST_ANGLE); + issues.clear(); + + //test good wrap around angle + opts.distributedAngleMode_lowerBound(350.234f); + opts.distributedAngleMode_upperBound(31.0f); + c.fatigueOptions(opts); + BOOST_CHECK_EQUAL(node.verifyConfig(c, issues), true); + + //test bad standard angles (too close) + opts.distributedAngleMode_lowerBound(49.5f); + opts.distributedAngleMode_upperBound(50.0f); + c.fatigueOptions(opts); + BOOST_CHECK_EQUAL(node.verifyConfig(c, issues), false); + BOOST_CHECK_EQUAL(issues.at(0).id(), ConfigIssue::CONFIG_FATIGUE_DIST_ANGLE); + issues.clear(); + + //test bad number of angles + opts.distributedAngleMode_lowerBound(1.0f); + opts.distributedAngleMode_upperBound(31.0f); + opts.distributedAngleMode_numAngles(3); + c.fatigueOptions(opts); + BOOST_CHECK_EQUAL(node.verifyConfig(c, issues), false); + BOOST_CHECK_EQUAL(issues.at(0).id(), ConfigIssue::CONFIG_FATIGUE_DIST_NUM_ANGLES); +} + BOOST_AUTO_TEST_SUITE_END() \ No newline at end of file diff --git a/MSCL_Unit_Tests/mock_BaseStation.h b/MSCL_Unit_Tests/mock_BaseStation.h index a7e562b69..36da7f966 100644 --- a/MSCL_Unit_Tests/mock_BaseStation.h +++ b/MSCL_Unit_Tests/mock_BaseStation.h @@ -17,6 +17,7 @@ LICENSE.txt file for a copy of the full GNU General Public License. #include "mscl/MicroStrain/Wireless/BaseStation_Impl.h" #include "mscl/MicroStrain/Wireless/BaseStationInfo.h" #include "mscl/MicroStrain/Wireless/Features/BaseStationFeatures.h" +#include "mscl/MicroStrain/Wireless/Configuration/BaseStationEepromMap.h" #include "mscl/Timestamp.h" #include @@ -67,6 +68,17 @@ static void expectWrite(std::shared_ptr impl, const Eeprom MOCK_EXPECT(impl->writeEeprom).with(loc, val); } +static void expectResetRadio(std::shared_ptr impl) +{ + expectWrite(impl, BaseStationEepromMap::CYCLE_POWER, Value::UINT16(2)); +} + +static void expectCyclePower(std::shared_ptr impl) +{ + expectWrite(impl, BaseStationEepromMap::CYCLE_POWER, Value::UINT16(1)); + MOCK_EXPECT(impl->ping).returns(true); +} + static BaseStation makeBaseStationWithMockImpl() { diff --git a/MSCL_Unit_Tests/mock_WirelessNode.h b/MSCL_Unit_Tests/mock_WirelessNode.h index 2d39329d9..54de567e2 100644 --- a/MSCL_Unit_Tests/mock_WirelessNode.h +++ b/MSCL_Unit_Tests/mock_WirelessNode.h @@ -25,19 +25,19 @@ using namespace mscl; MOCK_BASE_CLASS(mock_WirelessNodeImpl, WirelessNode_Impl) { mock_WirelessNodeImpl(): - WirelessNode_Impl(123, makeBaseStationWithMockImpl(), WirelessTypes::freq_unknown) + WirelessNode_Impl(123, makeBaseStationWithMockImpl()) {} mock_WirelessNodeImpl(BaseStation basestation): - WirelessNode_Impl(123, basestation, WirelessTypes::freq_unknown) + WirelessNode_Impl(123, basestation) {} mock_WirelessNodeImpl(uint16 address): - WirelessNode_Impl(address, makeBaseStationWithMockImpl(), WirelessTypes::freq_unknown) + WirelessNode_Impl(address, makeBaseStationWithMockImpl()) {} mock_WirelessNodeImpl(BaseStation basestation, uint16 address) : - WirelessNode_Impl(address, basestation, WirelessTypes::freq_unknown) + WirelessNode_Impl(address, basestation) { } @@ -54,22 +54,22 @@ MOCK_BASE_CLASS(mock_WirelessNodeImpl, WirelessNode_Impl) MOCK_BASE_CLASS(mock_WirelessNodeImpl_Basic, WirelessNode_Impl) { mock_WirelessNodeImpl_Basic(): - WirelessNode_Impl(123, makeBaseStationWithMockImpl(), WirelessTypes::freq_unknown) + WirelessNode_Impl(123, makeBaseStationWithMockImpl()) { } mock_WirelessNodeImpl_Basic(BaseStation basestation): - WirelessNode_Impl(123, basestation, WirelessTypes::freq_unknown) + WirelessNode_Impl(123, basestation) { } mock_WirelessNodeImpl_Basic(uint16 address): - WirelessNode_Impl(address, makeBaseStationWithMockImpl(), WirelessTypes::freq_unknown) + WirelessNode_Impl(address, makeBaseStationWithMockImpl()) { } mock_WirelessNodeImpl_Basic(BaseStation basestation, uint16 address): - WirelessNode_Impl(address, basestation, WirelessTypes::freq_unknown) + WirelessNode_Impl(address, basestation) { } @@ -120,6 +120,12 @@ static void expectResetRadio(std::shared_ptr impl) expectWrite(impl, NodeEepromMap::CYCLE_POWER, Value::UINT16(2)); } +static void expectCyclePower(std::shared_ptr impl) +{ + expectWrite(impl, NodeEepromMap::CYCLE_POWER, Value::UINT16(1)); + expectGoodPing(impl); +} + static void expectRead(std::shared_ptr impl, const EepromLocation& loc, const Value& returnVal) { MOCK_EXPECT(impl->readEeprom).with(loc).returns(returnVal);