summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--daemons/gptp/common/avbts_clock.hpp7
-rw-r--r--daemons/gptp/common/avbts_message.hpp44
-rw-r--r--daemons/gptp/common/avbts_osnet.hpp10
-rw-r--r--daemons/gptp/common/common_port.cpp70
-rw-r--r--daemons/gptp/common/common_port.hpp173
-rw-r--r--daemons/gptp/common/common_tstamper.hpp153
-rw-r--r--daemons/gptp/common/ether_port.cpp192
-rw-r--r--daemons/gptp/common/ether_port.hpp14
-rw-r--r--daemons/gptp/common/ether_tstamper.hpp73
-rw-r--r--daemons/gptp/common/gptp_cfg.cpp119
-rw-r--r--daemons/gptp/common/gptp_cfg.hpp62
-rw-r--r--daemons/gptp/common/ieee1588.hpp237
-rw-r--r--daemons/gptp/common/ieee1588clock.cpp40
-rw-r--r--daemons/gptp/common/ptp_message.cpp150
-rw-r--r--daemons/gptp/gptp_cfg.ini27
-rw-r--r--daemons/gptp/linux/src/daemon_cl.cpp51
-rw-r--r--daemons/gptp/linux/src/linux_hal_common.cpp76
-rw-r--r--daemons/gptp/linux/src/linux_hal_common.hpp17
-rw-r--r--daemons/gptp/linux/src/linux_hal_generic.cpp12
-rw-r--r--daemons/gptp/windows/daemon_cl/daemon_cl.cpp69
-rw-r--r--daemons/gptp/windows/daemon_cl/windows_hal.cpp39
-rw-r--r--daemons/gptp/windows/daemon_cl/windows_hal.hpp37
-rw-r--r--daemons/gptp/windows/gptp.sln38
23 files changed, 1033 insertions, 677 deletions
diff --git a/daemons/gptp/common/avbts_clock.hpp b/daemons/gptp/common/avbts_clock.hpp
index 750433da..feb8d9d1 100644
--- a/daemons/gptp/common/avbts_clock.hpp
+++ b/daemons/gptp/common/avbts_clock.hpp
@@ -137,8 +137,6 @@ private:
Timestamp _prev_local_time;
Timestamp _prev_system_time;
- HWTimestamper *_timestamper;
-
OS_IPC *ipc;
OSTimerQueue *timerq;
@@ -187,15 +185,14 @@ public:
* @param forceOrdinarySlave Forces it to be an ordinary slave
* @param syntonize if TRUE, clock will syntonize to the master clock
* @param priority1 It is used in the execution of BCMA. See IEEE 802.1AS-2011 Clause 10.3
- * @param timestamper [in] Provides an object for hardware timestamp
* @param timerq_factory [in] Provides a factory object for creating timer queues (managing events)
* @param ipc [in] Inter process communication object
* @param lock_factory [in] Provides a factory object for creating locking a locking mechanism
*/
IEEE1588Clock
(bool forceOrdinarySlave, bool syntonize, uint8_t priority1,
- HWTimestamper *timestamper, OSTimerQueueFactory * timerq_factory,
- OS_IPC * ipc, OSLockFactory *lock_factory );
+ OSTimerQueueFactory * timerq_factory, OS_IPC * ipc,
+ OSLockFactory *lock_factory );
/*
* Destroys the IEEE 1588 clock entity
diff --git a/daemons/gptp/common/avbts_message.hpp b/daemons/gptp/common/avbts_message.hpp
index 1b91dd03..f18d1213 100644
--- a/daemons/gptp/common/avbts_message.hpp
+++ b/daemons/gptp/common/avbts_message.hpp
@@ -277,6 +277,22 @@ protected:
}
/**
+ * @brief Check if message type is event
+ * @return true if an event message
+ */
+ bool isEvent( void )
+ {
+ return (( messageType >> 3) & 0x1 ) == 0;
+ }
+
+ /**
+ * @brief Get TX timestamp
+ * @param port used to send message
+ * @param link_speed link speed of message
+ */
+ bool getTxTimestamp( EtherPort *port, uint32_t link_speed );
+
+ /**
* @brief Gets the MessageID of the PTP message.
* @return MessageId
*/
@@ -586,9 +602,9 @@ class PTPMessageAnnounce:public PTPMessageCommon {
* @param port EtherPort where the message will be
* assembled
* @param destIdentity [in] Destination PortIdentity
- * @return void
+ * @return true on success
*/
- void sendPort
+ bool sendPort
( CommonPort *port, PortIdentity *destIdentity);
friend PTPMessageCommon *buildPTPMessage
@@ -637,9 +653,9 @@ class PTPMessageSync : public PTPMessageCommon {
* @param port EtherPort where the message will be
* assembled
* @param destIdentity [in] Destination PortIdentity
- * @return void
+ * @return true on success
*/
- void sendPort
+ bool sendPort
(EtherPort *port, PortIdentity *destIdentity );
friend PTPMessageCommon *buildPTPMessage
@@ -858,9 +874,9 @@ public:
* @param port EtherPort where the message will be
* assembled
* @param destIdentity [in] Destination PortIdentity
- * @return void
+ * @return true on success
*/
- void sendPort
+ bool sendPort
( EtherPort *port, PortIdentity *destIdentity );
/**
@@ -932,9 +948,9 @@ class PTPMessagePathDelayReq : public PTPMessageCommon {
* @param port EtherPort where the message will be
* assembled
* @param destIdentity [in] Destination PortIdentity
- * @return void
+ * @return true on success
*/
- void sendPort
+ bool sendPort
( EtherPort *port, PortIdentity *destIdentity );
/**
@@ -983,9 +999,9 @@ public:
* @param port EtherPort where the message will be
* assembled
* @param destIdentity [in] Destination PortIdentity
- * @return void
+ * @return true on success
*/
- void sendPort
+ bool sendPort
( EtherPort *port, PortIdentity *destIdentity );
/**
@@ -1057,9 +1073,9 @@ public:
* @param port EtherPort where the message will be
* assembled
* @param destIdentity [in] Destination PortIdentity
- * @return void
+ * @return true on success
*/
- void sendPort
+ bool sendPort
( EtherPort *port, PortIdentity *destIdentity );
/**
@@ -1246,9 +1262,9 @@ public:
* @param port EtherPort where the message will be
* assembled
* @param destIdentity [in] Destination PortIdentity
- * @return void
+ * @return true on success
*/
- void sendPort
+ bool sendPort
( EtherPort *port, PortIdentity *destIdentity );
/**
diff --git a/daemons/gptp/common/avbts_osnet.hpp b/daemons/gptp/common/avbts_osnet.hpp
index 1319326c..eb3194cb 100644
--- a/daemons/gptp/common/avbts_osnet.hpp
+++ b/daemons/gptp/common/avbts_osnet.hpp
@@ -42,6 +42,8 @@
/**@file*/
+class CommonTimestamper;
+
#define FACTORY_NAME_LENGTH 48 /*!< Factory name maximum length */
#define DEFAULT_TIMEOUT 1 /*!< Default timeout in milliseconds*/
@@ -313,7 +315,7 @@ class OSNetworkInterface {
* @return net_result enumeration
*/
virtual net_result nrecv
- (LinkLayerAddress * addr, uint8_t * payload, size_t & length, struct phy_delay *delay) = 0;
+ ( LinkLayerAddress *addr, uint8_t *payload, size_t &length ) = 0;
/**
* @brief Get Link Layer address (mac address)
@@ -372,12 +374,12 @@ class OSNetworkInterfaceFactory {
* @param iface [out] Pointer to interface name
* @param id Factory name index
* @param iflabel Interface label
- * @param timestamper HWTimestamper class pointer
+ * @param timestamper CommonTimestamper class pointer
* @return TRUE ok, FALSE error.
*/
static bool buildInterface
(OSNetworkInterface ** iface, factory_name_t id, InterfaceLabel * iflabel,
- HWTimestamper * timestamper) {
+ CommonTimestamper * timestamper) {
return factoryMap[id]->createInterface
(iface, iflabel, timestamper);
}
@@ -385,7 +387,7 @@ class OSNetworkInterfaceFactory {
private:
virtual bool createInterface
(OSNetworkInterface ** iface, InterfaceLabel * iflabel,
- HWTimestamper * timestamper) = 0;
+ CommonTimestamper * timestamper) = 0;
static FactoryMap_t factoryMap;
};
diff --git a/daemons/gptp/common/common_port.cpp b/daemons/gptp/common/common_port.cpp
index a5116083..be2d8159 100644
--- a/daemons/gptp/common/common_port.cpp
+++ b/daemons/gptp/common/common_port.cpp
@@ -34,6 +34,8 @@
#include <common_port.hpp>
#include <avbts_clock.hpp>
+#include <common_tstamper.hpp>
+#include <gptp_cfg.hpp>
CommonPort::CommonPort( PortInit_t *portInit ) :
thread_factory( portInit->thread_factory ),
@@ -42,16 +44,16 @@ CommonPort::CommonPort( PortInit_t *portInit ) :
condition_factory( portInit->condition_factory ),
_hw_timestamper( portInit->timestamper ),
clock( portInit->clock ),
- isGM( portInit->isGM )
+ isGM( portInit->isGM ),
+ phy_delay( portInit->phy_delay )
{
one_way_delay = ONE_WAY_DELAY_DEFAULT;
- neighbor_prop_delay_thresh = NEIGHBOR_PROP_DELAY_THRESH;
+ neighbor_prop_delay_thresh = portInit->neighborPropDelayThreshold;
net_label = portInit->net_label;
link_thread = thread_factory->createThread();
listening_thread = thread_factory->createThread();
- sync_receipt_thresh = DEFAULT_SYNC_RECEIPT_THRESH;
+ sync_receipt_thresh = portInit->syncReceiptThreshold;
wrongSeqIDCounter = 0;
- memset(phy_delay, 0, sizeof(phy_delay));
_peer_rate_offset = 1.0;
_peer_offset_init = false;
ifindex = portInit->index;
@@ -66,6 +68,7 @@ CommonPort::CommonPort( PortInit_t *portInit ) :
log_mean_announce_interval = 0;
pdelay_count = 0;
asCapable = false;
+ link_speed = INVALID_LINKSPEED;
}
CommonPort::~CommonPort()
@@ -73,7 +76,7 @@ CommonPort::~CommonPort()
delete qualified_announce;
}
-bool CommonPort::init_port( int phy_delay[4] )
+bool CommonPort::init_port( void )
{
log_mean_sync_interval = initialLogSyncInterval;
@@ -84,7 +87,6 @@ bool CommonPort::init_port( int phy_delay[4] )
this->net_iface->getLinkLayerAddress(&local_addr);
clock->setClockIdentity(&local_addr);
- memcpy(this->phy_delay, phy_delay, sizeof(this->phy_delay));
this->timestamper_init();
@@ -102,7 +104,6 @@ void CommonPort::timestamper_init( void )
{
if( _hw_timestamper != NULL )
{
- _hw_timestamper->init_phy_delay(this->phy_delay);
if( !_hw_timestamper->HWTimestamper_init
( net_label, net_iface ))
{
@@ -118,7 +119,6 @@ void CommonPort::timestamper_reset( void )
{
if( _hw_timestamper != NULL )
{
- _hw_timestamper->init_phy_delay(this->phy_delay);
_hw_timestamper->HWTimestamper_reset();
}
}
@@ -707,3 +707,57 @@ void CommonPort::startAnnounce()
{
startAnnounceIntervalTimer(16000000);
}
+
+int CommonPort::getTimestampVersion()
+{
+ return _hw_timestamper->getVersion();
+}
+
+bool CommonPort::_adjustClockRate( FrequencyRatio freq_offset )
+{
+ if( _hw_timestamper )
+ {
+ return _hw_timestamper->HWTimestamper_adjclockrate
+ ((float) freq_offset );
+ }
+
+ return false;
+}
+
+void CommonPort::getExtendedError( char *msg )
+{
+ if (_hw_timestamper)
+ {
+ _hw_timestamper->HWTimestamper_get_extderror(msg);
+ return;
+ }
+
+ *msg = '\0';
+}
+
+bool CommonPort::adjustClockPhase( int64_t phase_adjust )
+{
+ if( _hw_timestamper )
+ return _hw_timestamper->
+ HWTimestamper_adjclockphase( phase_adjust );
+
+ return false;
+}
+
+Timestamp CommonPort::getTxPhyDelay( uint32_t link_speed ) const
+{
+ if( phy_delay->count( link_speed ) != 0 )
+ return Timestamp
+ ( phy_delay->at(link_speed).get_tx_delay(), 0, 0 );
+
+ return Timestamp(0, 0, 0);
+}
+
+Timestamp CommonPort::getRxPhyDelay( uint32_t link_speed ) const
+{
+ if( phy_delay->count( link_speed ) != 0 )
+ return Timestamp
+ ( phy_delay->at(link_speed).get_rx_delay(), 0, 0 );
+
+ return Timestamp(0, 0, 0);
+}
diff --git a/daemons/gptp/common/common_port.hpp b/daemons/gptp/common/common_port.hpp
index da333a74..27800ad2 100644
--- a/daemons/gptp/common/common_port.hpp
+++ b/daemons/gptp/common/common_port.hpp
@@ -41,6 +41,7 @@
#include <avbts_ostimer.hpp>
#include <avbts_oslock.hpp>
#include <avbts_osnet.hpp>
+#include <unordered_map>
#include <math.h>
@@ -194,6 +195,9 @@ public:
}
};
+class phy_delay_spec_t;
+typedef std::unordered_map<uint32_t, phy_delay_spec_t> phy_delay_map_t;
+
/**
* @brief Structure for initializing the port class
*/
@@ -205,7 +209,7 @@ typedef struct {
uint16_t index;
/* timestamper Hardware timestamper instance */
- HWTimestamper * timestamper;
+ CommonTimestamper * timestamper;
/* net_label Network label */
InterfaceLabel *net_label;
@@ -248,6 +252,15 @@ typedef struct {
/* lock_factory OSLockFactory instance */
OSLockFactory * lock_factory;
+
+ /* phy delay */
+ phy_delay_map_t const *phy_delay;
+
+ /* sync receipt threshold */
+ unsigned int syncReceiptThreshold;
+
+ /* neighbor delay threshold */
+ int64_t neighborPropDelayThreshold;
} PortInit_t;
@@ -273,7 +286,6 @@ typedef struct {
int32_t ieee8021AsPortStatTxAnnounce;
} PortCounters_t;
-
/**
* @brief Port functionality common to all network media
*/
@@ -287,6 +299,8 @@ private:
physical interface number that object represents */
uint16_t ifindex;
+ /* Link speed in kb/sec */
+ uint32_t link_speed;
/* Signed value allows this to be negative result because of inaccurate
timestamp */
@@ -296,7 +310,6 @@ private:
InterfaceLabel *net_label;
OSNetworkInterface *net_iface;
- int phy_delay[4];
PortState port_state;
bool testMode;
@@ -336,30 +349,31 @@ private:
OSLock *announceIntervalTimerLock;
protected:
- static const unsigned int DEFAULT_SYNC_RECEIPT_THRESH = 5;
static const int64_t INVALID_LINKDELAY = 3600000000000;
static const int64_t ONE_WAY_DELAY_DEFAULT = INVALID_LINKDELAY;
- static const int64_t NEIGHBOR_PROP_DELAY_THRESH = 800;
OSThreadFactory const * const thread_factory;
OSTimerFactory const * const timer_factory;
OSLockFactory const * const lock_factory;
OSConditionFactory const * const condition_factory;
- HWTimestamper * const _hw_timestamper;
+ CommonTimestamper * const _hw_timestamper;
IEEE1588Clock * const clock;
const bool isGM;
+ phy_delay_map_t const * const phy_delay;
+
public:
+ static const int64_t NEIGHBOR_PROP_DELAY_THRESH = 800;
+ static const unsigned int DEFAULT_SYNC_RECEIPT_THRESH = 5;
+
CommonPort( PortInit_t *portInit );
virtual ~CommonPort();
/**
* @brief Global media dependent port initialization
- * @param [in] phy_delay array representing delays introduced by the
- * device PHY
* @return true on success
*/
- bool init_port( int phy_delay[4] );
+ bool init_port( void );
/**
* @brief Media specific port initialization
@@ -570,22 +584,14 @@ public:
* @brief Gets the hardware timestamper version
* @return HW timestamper version
*/
- int getTimestampVersion() {
- return _hw_timestamper->getVersion();
- }
+ int getTimestampVersion();
/**
* @brief Adjusts the clock frequency.
* @param freq_offset Frequency offset
* @return TRUE if adjusted. FALSE otherwise.
*/
- bool _adjustClockRate( FrequencyRatio freq_offset ) {
- if( _hw_timestamper ) {
- return _hw_timestamper->HWTimestamper_adjclockrate
- ((float) freq_offset );
- }
- return false;
- }
+ bool _adjustClockRate( FrequencyRatio freq_offset );
/**
* @brief Adjusts the clock frequency.
@@ -597,17 +603,18 @@ public:
}
/**
+ * @brief Adjusts the clock phase.
+ * @param phase_adjust phase offset in ns
+ * @return TRUE if adjusted. FALSE otherwise.
+ */
+ bool adjustClockPhase( int64_t phase_adjust );
+
+ /**
* @brief Gets extended error message from hardware timestamper
* @param msg [out] Extended error message
* @return void
*/
- void getExtendedError(char *msg) {
- if (_hw_timestamper) {
- _hw_timestamper->HWTimestamper_get_extderror(msg);
- } else {
- *msg = '\0';
- }
- }
+ void getExtendedError(char *msg);
/**
* @brief Increment IEEE Port counter:
@@ -983,17 +990,21 @@ public:
/**
* @brief Receive frame
*/
- net_result recv( LinkLayerAddress *addr, uint8_t *payload,
- size_t &length, struct phy_delay *delay )
+ net_result recv
+ ( LinkLayerAddress *addr, uint8_t *payload, size_t &length,
+ uint32_t &link_speed )
{
- return net_iface->nrecv( addr, payload, length, delay );
+ net_result result = net_iface->nrecv( addr, payload, length );
+ link_speed = this->link_speed;
+ return result;
}
/**
* @brief Send frame
*/
- net_result send( LinkLayerAddress *addr, uint16_t etherType,
- uint8_t *payload, size_t length, bool timestamp )
+ net_result send
+ ( LinkLayerAddress *addr, uint16_t etherType, uint8_t *payload,
+ size_t length, bool timestamp )
{
return net_iface->send
( addr, etherType, payload, length, timestamp );
@@ -1339,6 +1350,106 @@ public:
virtual void sendGeneralPort
(uint16_t etherType, uint8_t * buf, int len, MulticastType mcast_type,
PortIdentity * destIdentity) = 0;
+
+ /**
+ * @brief Sets link speed
+ */
+ void setLinkSpeed( uint32_t link_speed )
+ {
+ this->link_speed = link_speed;
+ }
+
+ /**
+ * @brief Returns link speed
+ */
+ uint32_t getLinkSpeed( void )
+ {
+ return link_speed;
+ }
+
+ /**
+ * @brief Returns TX PHY delay
+ */
+ Timestamp getTxPhyDelay( uint32_t link_speed ) const;
+
+ /**
+ * @brief Returns RX PHY delay
+ */
+ Timestamp getRxPhyDelay( uint32_t link_speed ) const;
+};
+
+/**
+ * @brief Specifies a RX/TX PHY compensation pair
+ */
+class phy_delay_spec_t
+{
+private:
+ uint16_t tx_delay;
+ uint16_t rx_delay;
+public:
+ /**
+ * Constructor setting PHY compensation
+ */
+ phy_delay_spec_t(
+ uint16_t tx_delay,
+ uint16_t rx_delay )
+ {
+ this->tx_delay = tx_delay;
+ this->rx_delay = rx_delay;
+ }
+
+ /**
+ * Default constructor sets 0 PHY compensation
+ */
+ phy_delay_spec_t()
+ {
+ phy_delay_spec_t( 0, 0 );
+ }
+
+ /**
+ * @brief sets PHY compensation
+ */
+ void set_delay(
+ uint16_t tx_delay,
+ uint16_t rx_delay )
+ {
+ this->tx_delay = tx_delay;
+ this->rx_delay = rx_delay;
+ }
+
+ /**
+ * @brief sets RX PHY compensation
+ */
+ void set_tx_delay(
+ uint16_t tx_delay )
+ {
+ this->tx_delay = tx_delay;
+ }
+
+ /**
+ * @brief sets TX PHY compensation
+ */
+ void set_rx_delay(
+ uint16_t rx_delay )
+ {
+ this->rx_delay = rx_delay;
+ }
+
+ /**
+ * @brief gets TX PHY compensation
+ */
+ uint16_t get_tx_delay() const
+ {
+ return tx_delay;
+ }
+
+ /**
+ * @brief gets RX PHY compensation
+ */
+ uint16_t get_rx_delay() const
+ {
+ return rx_delay;
+ }
};
#endif/*COMMON_PORT_HPP*/
diff --git a/daemons/gptp/common/common_tstamper.hpp b/daemons/gptp/common/common_tstamper.hpp
new file mode 100644
index 00000000..cfaf3abd
--- /dev/null
+++ b/daemons/gptp/common/common_tstamper.hpp
@@ -0,0 +1,153 @@
+/******************************************************************************
+
+ Copyright (c) 2009-2012, Intel Corporation
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+
+ 1. Redistributions of source code must retain the above copyright notice,
+ this list of conditions and the following disclaimer.
+
+ 2. Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+
+ 3. Neither the name of the Intel Corporation nor the names of its
+ contributors may be used to endorse or promote products derived from
+ this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ POSSIBILITY OF SUCH DAMAGE.
+
+******************************************************************************/
+
+#ifndef COMMON_TSTAMPER_HPP
+#define COMMON_TSTAMPER_HPP
+
+#include <unordered_map>
+#include <stdint.h>
+#include <avbts_message.hpp>
+
+#define HWTIMESTAMPER_EXTENDED_MESSAGE_SIZE 4096 /*!< Maximum size of HWTimestamper extended message */
+
+/**
+ * @brief Provides a generic interface for hardware timestamping
+ */
+class CommonTimestamper {
+protected:
+ uint8_t version; //!< HWTimestamper version
+
+public:
+ /**
+ * @brief Initializes the hardware timestamp unit
+ * @param iface_label [in] Interface label
+ * @param iface [in] Network interface
+ * @return true
+ */
+ virtual bool HWTimestamper_init
+ ( InterfaceLabel *iface_label, OSNetworkInterface *iface )
+ { return true; }
+
+ /**
+ * @brief Reset the hardware timestamp unit
+ * @return void
+ */
+ virtual void HWTimestamper_reset(void) {
+ }
+
+ /**
+ * @brief This method is called before the object is de-allocated.
+ * @return void
+ */
+ virtual void HWTimestamper_final(void) {
+ }
+
+ /**
+ * @brief Adjusts the hardware clock frequency
+ * @param frequency_offset Frequency offset
+ * @return false
+ */
+ virtual bool HWTimestamper_adjclockrate
+ ( float frequency_offset ) const
+ { return false; }
+
+ /**
+ * @brief Adjusts the hardware clock phase
+ * @param phase_adjust Phase offset
+ * @return false
+ */
+ virtual bool HWTimestamper_adjclockphase( int64_t phase_adjust )
+ { return false; }
+
+ /**
+ * @brief Get the cross timestamping information.
+ * The gPTP subsystem uses these samples to calculate
+ * ratios which can be used to translate or extrapolate
+ * one clock into another clock reference. The gPTP service
+ * uses these supplied cross timestamps to perform internal
+ * rate estimation and conversion functions.
+ * @param system_time [out] System time
+ * @param device_time [out] Device time
+ * @param local_clock [out] Local clock
+ * @param nominal_clock_rate [out] Nominal clock rate
+ * @return True in case of success. FALSE in case of error
+ */
+ virtual bool HWTimestamper_gettime(Timestamp * system_time,
+ Timestamp * device_time,
+ uint32_t * local_clock,
+ uint32_t * nominal_clock_rate) const = 0;
+
+ /**
+ * @brief Gets a string with the error from the hardware timestamp block
+ * @param msg [out] String error
+ * @return void
+ * @todo There is no current implementation for this method.
+ */
+ virtual void HWTimestamper_get_extderror(char *msg) const
+ {
+ *msg = '\0';
+ }
+
+ /**
+ * @brief Starts the PPS (pulse per second) interface
+ * @return false
+ */
+ virtual bool HWTimestamper_PPS_start() { return false; };
+
+ /**
+ * @brief Stops the PPS (pulse per second) interface
+ * @return true
+ */
+ virtual bool HWTimestamper_PPS_stop() { return true; };
+
+ /**
+ * @brief Gets the HWTimestamper version
+ * @return version (signed integer)
+ */
+ int getVersion() const
+ {
+ return version;
+ }
+
+ /**
+ * @brief Default constructor. Sets version to zero.
+ */
+ CommonTimestamper() { version = 0; }
+
+ /**
+ * @brief Deletes HWtimestamper object
+ */
+ virtual ~CommonTimestamper() { }
+};
+
+#endif/*COMMON_TSTAMPER_HPP*/
diff --git a/daemons/gptp/common/ether_port.cpp b/daemons/gptp/common/ether_port.cpp
index 83400285..8735987c 100644
--- a/daemons/gptp/common/ether_port.cpp
+++ b/daemons/gptp/common/ether_port.cpp
@@ -40,6 +40,7 @@
#include <avbts_oslock.hpp>
#include <avbts_osnet.hpp>
#include <avbts_oscondition.hpp>
+#include <ether_tstamper.hpp>
#include <gptp_log.hpp>
@@ -208,35 +209,53 @@ void EtherPort::startSyncRateIntervalTimer()
}
}
+void EtherPort::processMessage
+( char *buf, int length, LinkLayerAddress *remote, uint32_t link_speed )
+{
+ GPTP_LOG_VERBOSE("Processing network buffer");
+
+ PTPMessageCommon *msg =
+ buildPTPMessage( buf, (int)length, remote, this );
+
+ if (msg == NULL)
+ {
+ GPTP_LOG_ERROR("Discarding invalid message");
+ return;
+ }
+ GPTP_LOG_VERBOSE("Processing message");
+
+ if( msg->isEvent() )
+ {
+ Timestamp rx_timestamp = msg->getTimestamp();
+ Timestamp phy_compensation = getRxPhyDelay( link_speed );
+ GPTP_LOG_DEBUG( "RX PHY compensation: %s sec",
+ phy_compensation.toString().c_str() );
+ phy_compensation._version = rx_timestamp._version;
+ rx_timestamp = rx_timestamp - phy_compensation;
+ msg->setTimestamp( rx_timestamp );
+ }
+
+ msg->processMessage(this);
+ if (msg->garbage())
+ delete msg;
+}
+
void *EtherPort::openPort( EtherPort *port )
{
port_ready_condition->signal();
- struct phy_delay get_delay = { 0, 0, 0, 0 };
- if(port->_hw_timestamper)
- port->_hw_timestamper->get_phy_delay(&get_delay);
while (1) {
- PTPMessageCommon *msg;
uint8_t buf[128];
LinkLayerAddress remote;
net_result rrecv;
size_t length = sizeof(buf);
+ uint32_t link_speed;
- if ((rrecv = recv(&remote, buf, length,&get_delay))
- == net_succeed)
+ if ( ( rrecv = recv( &remote, buf, length, link_speed ))
+ == net_succeed )
{
- GPTP_LOG_VERBOSE("Processing network buffer");
- msg = buildPTPMessage((char *)buf, (int)length, &remote,
- this);
- if (msg != NULL) {
- GPTP_LOG_VERBOSE("Processing message");
- msg->processMessage(this);
- if (msg->garbage()) {
- delete msg;
- }
- } else {
- GPTP_LOG_ERROR("Discarding invalid message");
- }
+ processMessage
+ ((char *)buf, (int)length, &remote, link_speed );
} else if (rrecv == net_fatal) {
GPTP_LOG_ERROR("read from network interface failed");
this->processEvent(FAULT_DETECTED);
@@ -271,14 +290,19 @@ net_result EtherPort::port_send
}
void EtherPort::sendEventPort
-( uint16_t etherType, uint8_t * buf, int size, MulticastType mcast_type,
- PortIdentity * destIdentity)
+( uint16_t etherType, uint8_t *buf, int size, MulticastType mcast_type,
+ PortIdentity *destIdentity, uint32_t *link_speed )
{
- net_result rtx = port_send(etherType, buf, size, mcast_type, destIdentity, true);
- if (rtx != net_succeed) {
+ net_result rtx = port_send
+ ( etherType, buf, size, mcast_type, destIdentity, true );
+ if( rtx != net_succeed )
+ {
GPTP_LOG_ERROR("sendEventPort(): failure");
+ return;
}
+ *link_speed = this->getLinkSpeed();
+
return;
}
@@ -471,12 +495,7 @@ bool EtherPort::_processEvent( Event e )
case PDELAY_INTERVAL_TIMEOUT_EXPIRES:
GPTP_LOG_DEBUG("PDELAY_INTERVAL_TIMEOUT_EXPIRES occured");
{
- int ts_good;
Timestamp req_timestamp;
- int iter = TX_TIMEOUT_ITER;
- long req = TX_TIMEOUT_BASE;
- unsigned req_timestamp_counter_value;
- long long wait_time = 0;
PTPMessagePathDelayReq *pdelay_req =
new PTPMessagePathDelayReq(this);
@@ -498,68 +517,27 @@ bool EtherPort::_processEvent( Event e )
getTxLock();
pdelay_req->sendPort(this, NULL);
GPTP_LOG_DEBUG("*** Sent PDelay Request message");
-
- OSTimer *timer = timer_factory->createTimer();
-
- ts_good = getTxTimestamp
- (pdelay_req, req_timestamp, req_timestamp_counter_value, false);
- while (ts_good != GPTP_EC_SUCCESS && iter-- != 0) {
- timer->sleep(req);
- wait_time += req;
- if (ts_good != GPTP_EC_EAGAIN && iter < 1)
- GPTP_LOG_ERROR(
- "Error (TX) timestamping PDelay request "
- "(Retrying-%d), error=%d", iter, ts_good);
- ts_good =
- getTxTimestamp
- (pdelay_req, req_timestamp,
- req_timestamp_counter_value, iter == 0);
- req *= 2;
- }
- delete timer;
putTxLock();
- if (ts_good == GPTP_EC_SUCCESS) {
- pdelay_req->setTimestamp(req_timestamp);
- GPTP_LOG_DEBUG(
- "PDelay Request message, Timestamp %u (sec) %u (ns), seqID %u",
- req_timestamp.seconds_ls, req_timestamp.nanoseconds,
- pdelay_req->getSequenceId());
- } else {
- Timestamp failed = INVALID_TIMESTAMP;
- pdelay_req->setTimestamp(failed);
- GPTP_LOG_ERROR( "Invalid TX" );
- }
-
- if (ts_good != GPTP_EC_SUCCESS) {
- char msg
- [HWTIMESTAMPER_EXTENDED_MESSAGE_SIZE];
- getExtendedError(msg);
- GPTP_LOG_ERROR(
- "Error (TX) timestamping PDelay request, error=%d\t%s",
- ts_good, msg);
- }
-
{
long long timeout;
long long interval;
timeout = PDELAY_RESP_RECEIPT_TIMEOUT_MULTIPLIER *
((long long)
- (pow((double)2,getPDelayInterval())*1000000000.0)) -
- wait_time*1000;
+ (pow((double)2,getPDelayInterval())*1000000000.0));
+
timeout = timeout > EVENT_TIMER_GRANULARITY ?
timeout : EVENT_TIMER_GRANULARITY;
clock->addEventTimerLocked
(this, PDELAY_RESP_RECEIPT_TIMEOUT_EXPIRES, timeout );
GPTP_LOG_DEBUG("Schedule PDELAY_RESP_RECEIPT_TIMEOUT_EXPIRES, "
- "PDelay interval %d, wait_time %lld, timeout %lld",
- getPDelayInterval(), wait_time, timeout);
+ "PDelay interval %d, timeout %lld",
+ getPDelayInterval(), timeout);
interval =
((long long)
- (pow((double)2,getPDelayInterval())*1000000000.0)) -
- wait_time*1000;
+ (pow((double)2,getPDelayInterval())*1000000000.0));
interval = interval > EVENT_TIMER_GRANULARITY ?
interval : EVENT_TIMER_GRANULARITY;
startPDelayIntervalTimer(interval);
@@ -574,10 +552,11 @@ bool EtherPort::_processEvent( Event e )
// Send a sync message and then a followup to broadcast
PTPMessageSync *sync = new PTPMessageSync(this);
PortIdentity dest_id;
+ bool tx_succeed;
getPortIdentity(dest_id);
sync->setPortIdentity(&dest_id);
getTxLock();
- sync->sendPort(this, NULL);
+ tx_succeed = sync->sendPort(this, NULL);
GPTP_LOG_DEBUG("Sent SYNC message");
if ( automotive_profile &&
@@ -598,44 +577,10 @@ bool EtherPort::_processEvent( Event e )
}
}
}
-
- int ts_good;
- Timestamp sync_timestamp;
- unsigned sync_timestamp_counter_value;
- int iter = TX_TIMEOUT_ITER;
- long req = TX_TIMEOUT_BASE;
-
- OSTimer *timer = timer_factory->createTimer();
-
- ts_good = getTxTimestamp( sync, sync_timestamp,
- sync_timestamp_counter_value,
- false );
- while (ts_good != GPTP_EC_SUCCESS && iter-- != 0) {
- timer->sleep(req);
-
- if (ts_good != GPTP_EC_EAGAIN && iter < 1)
- GPTP_LOG_ERROR(
- "Error (TX) timestamping Sync (Retrying), "
- "error=%d", ts_good);
- ts_good =
- getTxTimestamp
- (sync, sync_timestamp,
- sync_timestamp_counter_value, iter == 0);
- req *= 2;
- }
- delete timer;
putTxLock();
- if (ts_good != GPTP_EC_SUCCESS) {
- char msg [HWTIMESTAMPER_EXTENDED_MESSAGE_SIZE];
- getExtendedError(msg);
- GPTP_LOG_ERROR(
- "Error (TX) timestamping Sync, error="
- "%d\n%s",
- ts_good, msg );
- }
-
- if (ts_good == GPTP_EC_SUCCESS) {
+ if ( tx_succeed )
+ {
GPTP_LOG_VERBOSE("Successful Sync timestamp");
GPTP_LOG_VERBOSE("Seconds: %u",
sync_timestamp.seconds_ls);
@@ -647,8 +592,10 @@ bool EtherPort::_processEvent( Event e )
}
PTPMessageFollowUp *follow_up;
- if (ts_good == GPTP_EC_SUCCESS) {
-
+ if ( tx_succeed )
+ {
+ Timestamp sync_timestamp =
+ sync->getTimestamp();
follow_up =
new PTPMessageFollowUp(this);
PortIdentity dest_id;
@@ -657,7 +604,8 @@ bool EtherPort::_processEvent( Event e )
follow_up->setClockSourceTime(getClock()->getFUPInfo());
follow_up->setPortIdentity(&dest_id);
follow_up->setSequenceId(sync->getSequenceId());
- follow_up->setPreciseOriginTimestamp(sync_timestamp);
+ follow_up->setPreciseOriginTimestamp
+ (sync_timestamp);
follow_up->sendPort(this, NULL);
delete follow_up;
} else {
@@ -842,10 +790,13 @@ int EtherPort::getTxTimestamp
(PortIdentity *sourcePortIdentity, PTPMessageId messageId,
Timestamp &timestamp, unsigned &counter_value, bool last )
{
- if (_hw_timestamper) {
- return _hw_timestamper->HWTimestamper_txtimestamp
- (sourcePortIdentity, messageId, timestamp, counter_value,
- last);
+ EtherTimestamper *timestamper =
+ dynamic_cast<EtherTimestamper *>(_hw_timestamper);
+ if (timestamper)
+ {
+ return timestamper->HWTimestamper_txtimestamp
+ ( sourcePortIdentity, messageId, timestamp,
+ counter_value, last );
}
timestamp = clock->getSystemTime();
return 0;
@@ -855,8 +806,11 @@ int EtherPort::getRxTimestamp
( PortIdentity * sourcePortIdentity, PTPMessageId messageId,
Timestamp &timestamp, unsigned &counter_value, bool last )
{
- if (_hw_timestamper) {
- return _hw_timestamper->HWTimestamper_rxtimestamp
+ EtherTimestamper *timestamper =
+ dynamic_cast<EtherTimestamper *>(_hw_timestamper);
+ if (timestamper)
+ {
+ return timestamper->HWTimestamper_rxtimestamp
(sourcePortIdentity, messageId, timestamp, counter_value,
last);
}
diff --git a/daemons/gptp/common/ether_port.hpp b/daemons/gptp/common/ether_port.hpp
index 6028ca75..9d621e39 100644
--- a/daemons/gptp/common/ether_port.hpp
+++ b/daemons/gptp/common/ether_port.hpp
@@ -231,6 +231,17 @@ protected:
void recoverPort(void);
/**
+ * @brief Message processing logic on receipt
+ * @param [in] buf buffer containing message
+ * @param [in] length buffer length
+ * @param [in] remote address of sender
+ * @param [in] link_speed of the receiving device
+ */
+ void processMessage
+ ( char *buf, int length, LinkLayerAddress *remote,
+ uint32_t link_speed );
+
+ /**
* @brief Receives messages from the network interface
* @return Its an infinite loop. Returns NULL in case of error.
*/
@@ -242,11 +253,12 @@ protected:
* @param len Size of the message
* @param mcast_type Enumeration MulticastType (pdlay, none or other). Depracated.
* @param destIdentity Destination port identity
+ * @param [out] link_speed indicates link speed
* @return void
*/
void sendEventPort
(uint16_t etherType, uint8_t * buf, int len, MulticastType mcast_type,
- PortIdentity * destIdentity);
+ PortIdentity * destIdentity, uint32_t *link_speed );
/**
* @brief Sends a general message to a port. No timestamps
diff --git a/daemons/gptp/common/ether_tstamper.hpp b/daemons/gptp/common/ether_tstamper.hpp
new file mode 100644
index 00000000..bc590cbc
--- /dev/null
+++ b/daemons/gptp/common/ether_tstamper.hpp
@@ -0,0 +1,73 @@
+/******************************************************************************
+
+ Copyright (c) 2009-2012, Intel Corporation
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+
+ 1. Redistributions of source code must retain the above copyright notice,
+ this list of conditions and the following disclaimer.
+
+ 2. Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+
+ 3. Neither the name of the Intel Corporation nor the names of its
+ contributors may be used to endorse or promote products derived from
+ this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ POSSIBILITY OF SUCH DAMAGE.
+
+******************************************************************************/
+
+#ifndef ETHER_TSTAMPER_HPP
+#define ETHER_TSTAMPER_HPP
+
+#include <common_tstamper.hpp>
+
+class EtherTimestamper : public CommonTimestamper
+{
+public:
+ /**
+ * @brief Gets the tx timestamp from hardware
+ * @param identity PTP port identity
+ * @param PTPMessageId Message ID
+ * @param timestamp [out] Timestamp value
+ * @param clock_value [out] Clock value
+ * @param last Signalizes that it is the last timestamp to get. When TRUE, releases the lock when its done.
+ * @return GPTP_EC_SUCCESS if no error, GPTP_EC_FAILURE if error and GPTP_EC_EAGAIN to try again.
+ */
+ virtual int HWTimestamper_txtimestamp
+ ( PortIdentity * identity, PTPMessageId messageId,
+ Timestamp &timestamp, unsigned &clock_value, bool last ) = 0;
+
+ /**
+ * @brief Get rx timestamp
+ * @param identity PTP port identity
+ * @param messageId Message ID
+ * @param timestamp [out] Timestamp value
+ * @param clock_value [out] Clock value
+ * @param last Signalizes that it is the last timestamp to get. When TRUE, releases the lock when its done.
+ * @return GPTP_EC_SUCCESS if no error, GPTP_EC_FAILURE if error and GPTP_EC_EAGAIN to try again.
+ */
+ virtual int HWTimestamper_rxtimestamp(PortIdentity * identity,
+ PTPMessageId messageId,
+ Timestamp & timestamp,
+ unsigned &clock_value,
+ bool last) = 0;
+
+ virtual ~EtherTimestamper() {}
+};
+
+#endif/*ETHER_TSTAMPER_HPP*/
diff --git a/daemons/gptp/common/gptp_cfg.cpp b/daemons/gptp/common/gptp_cfg.cpp
index 3c6e37ef..fae8e6c0 100644
--- a/daemons/gptp/common/gptp_cfg.cpp
+++ b/daemons/gptp/common/gptp_cfg.cpp
@@ -48,6 +48,8 @@ https://github.com/benhoyt/inih/commit/74d2ca064fb293bc60a77b0bd068075b293cf175.
#include "gptp_cfg.hpp"
+uint32_t findSpeedByName( const char *name, const char **end );
+
GptpIniParser::GptpIniParser(std::string filename)
{
_error = ini_parse(filename.c_str(), iniCallBack, this);
@@ -156,7 +158,7 @@ int GptpIniParser::iniCallBack(void *user, const char *section, const char *name
int phdly = strtoul(value, &pEnd, 10);
if( *pEnd == '\0' && errno == 0) {
valOK = true;
- parser->_config.phyDelay.gb_tx_phy_delay = phdly;
+ parser->_config.phy_delay[LINKSPEED_1G].set_tx_delay( phdly );
}
}
@@ -167,7 +169,7 @@ int GptpIniParser::iniCallBack(void *user, const char *section, const char *name
int phdly = strtoul(value, &pEnd, 10);
if( *pEnd == '\0' && errno == 0) {
valOK = true;
- parser->_config.phyDelay.gb_rx_phy_delay = phdly;
+ parser->_config.phy_delay[LINKSPEED_1G].set_rx_delay( phdly );
}
}
@@ -178,7 +180,8 @@ int GptpIniParser::iniCallBack(void *user, const char *section, const char *name
int phdly = strtoul(value, &pEnd, 10);
if( *pEnd == '\0' && errno == 0) {
valOK = true;
- parser->_config.phyDelay.mb_tx_phy_delay = phdly;
+ parser->_config.phy_delay[LINKSPEED_100MB].
+ set_tx_delay( phdly );
}
}
@@ -189,7 +192,28 @@ int GptpIniParser::iniCallBack(void *user, const char *section, const char *name
int phdly = strtoul(value, &pEnd, 10);
if( *pEnd == '\0' && errno == 0) {
valOK = true;
- parser->_config.phyDelay.mb_rx_phy_delay = phdly;
+ parser->_config.phy_delay[LINKSPEED_100MB].
+ set_rx_delay( phdly );
+ }
+ }
+
+ else if( parseMatch(name, "phy_delay") )
+ {
+ errno = 0;
+ char *pEnd;
+ const char *c_pEnd;
+ uint32_t speed = findSpeedByName( value, &c_pEnd );
+ if( speed == INVALID_LINKSPEED )
+ {
+ speed = strtoul( value, &pEnd, 10 );
+ c_pEnd = pEnd;
+ }
+ int ph_tx_dly = strtoul(c_pEnd, &pEnd, 10);
+ int ph_rx_dly = strtoul(pEnd, &pEnd, 10);
+ if( *pEnd == '\0' && errno == 0) {
+ valOK = true;
+ parser->_config.phy_delay[speed].
+ set_delay( ph_tx_dly, ph_rx_dly );
}
}
}
@@ -211,3 +235,90 @@ bool GptpIniParser::parseMatch(const char *s1, const char *s2)
return strcasecmp(s1, s2) == 0;
}
+#define PHY_DELAY_DESC_LEN 21
+
+void GptpIniParser::print_phy_delay( void )
+{
+
+ phy_delay_map_t map = this->getPhyDelay();
+ for( phy_delay_map_t::const_iterator i = map.cbegin();
+ i != map.cend(); ++i )
+ {
+ uint32_t speed;
+ uint16_t tx, rx;
+ const char *speed_name;
+ char phy_delay_desc[PHY_DELAY_DESC_LEN+1];
+
+ speed = (*i).first;
+ tx = i->second.get_tx_delay();
+ rx = i->second.get_rx_delay();
+
+ snprintf( phy_delay_desc, PHY_DELAY_DESC_LEN+1,
+ "TX: %hu | RX: %hu", tx, rx );
+
+ speed_name = findNameBySpeed( speed );
+ if( speed_name != NULL )
+ GPTP_LOG_INFO( "%s - PHY delay\n\t\t\t%s",
+ speed_name, phy_delay_desc );
+ else
+ GPTP_LOG_INFO( "link speed %u - PHY delay\n\t\t\t%s",
+ speed, phy_delay_desc );
+ }
+}
+
+
+#define DECLARE_SPEED_NAME_MAP( name ) \
+ { name, #name }
+
+typedef struct
+{
+ const uint32_t speed;
+ const char *name;
+} speed_name_map_t;
+
+speed_name_map_t speed_name_map[] =
+{
+ DECLARE_SPEED_NAME_MAP( LINKSPEED_10G ),
+ DECLARE_SPEED_NAME_MAP( LINKSPEED_2_5G ),
+ DECLARE_SPEED_NAME_MAP( LINKSPEED_1G ),
+ DECLARE_SPEED_NAME_MAP( LINKSPEED_100MB ),
+ DECLARE_SPEED_NAME_MAP( INVALID_LINKSPEED )
+};
+
+const char *findNameBySpeed( uint32_t speed )
+{
+ speed_name_map_t *iter = speed_name_map;
+
+ while( iter->speed != INVALID_LINKSPEED )
+ {
+ if( iter->speed == speed )
+ {
+ break;
+ }
+ ++iter;
+ }
+
+ if( iter->speed != INVALID_LINKSPEED )
+ return iter->name;
+
+ return NULL;
+}
+
+uint32_t findSpeedByName( const char *name, const char **end )
+{
+ speed_name_map_t *iter = speed_name_map;
+ *end = name;
+
+ while( iter->speed != INVALID_LINKSPEED )
+ {
+ if( strncmp( name, iter->name, strlen( iter->name )) == 0 )
+ {
+ *end = name + strlen( iter->name );
+ break;
+ }
+ ++iter;
+ }
+
+ return iter->speed;
+}
+
diff --git a/daemons/gptp/common/gptp_cfg.hpp b/daemons/gptp/common/gptp_cfg.hpp
index 62bf149a..f283a4db 100644
--- a/daemons/gptp/common/gptp_cfg.hpp
+++ b/daemons/gptp/common/gptp_cfg.hpp
@@ -37,7 +37,20 @@ https://github.com/benhoyt/inih/commit/74d2ca064fb293bc60a77b0bd068075b293cf175.
#include <string>
#include "ini.h"
-#include "ieee1588.hpp"
+#include <limits.h>
+#include <common_port.hpp>
+
+const uint32_t LINKSPEED_10G = 10000000;
+const uint32_t LINKSPEED_2_5G = 2500000;
+const uint32_t LINKSPEED_1G = 1000000;
+const uint32_t LINKSPEED_100MB = 100000;
+const uint32_t INVALID_LINKSPEED = UINT_MAX;
+
+/**
+ * @brief Returns name given numeric link speed
+ * @return NULL if speed/name isn't found
+ */
+const char *findNameBySpeed( uint32_t speed );
/**
* @brief Provides the gptp interface for
@@ -65,8 +78,8 @@ class GptpIniParser
PortState port_state;
/*ethernet adapter data set*/
- std::string ifname;
- struct phy_delay phyDelay;
+ std::string ifname;
+ phy_delay_map_t phy_delay;
} gptp_cfg_t;
/*public methods*/
@@ -111,43 +124,13 @@ class GptpIniParser
}
/**
- * @brief Reads the TX PHY DELAY GB value from the configuration file
- * @param void
- * @return gb_tx_phy_delay value from the .ini file
- */
- int getPhyDelayGbTx(void)
- {
- return _config.phyDelay.gb_tx_phy_delay;
- }
-
- /**
- * @brief Reads the RX PHY DELAY GB value from the configuration file
+ * @brief Reads the PHY DELAY values from the configuration file
* @param void
- * @return gb_rx_phy_delay value from the .ini file
+ * @return PHY delay map structure
*/
- int getPhyDelayGbRx(void)
+ const phy_delay_map_t getPhyDelay(void)
{
- return _config.phyDelay.gb_rx_phy_delay;
- }
-
- /**
- * @brief Reads the TX PHY DELAY MB value from the configuration file
- * @param void
- * @return mb_tx_phy_delay value from the .ini file
- */
- int getPhyDelayMbTx(void)
- {
- return _config.phyDelay.mb_tx_phy_delay;
- }
-
- /**
- * @brief Reads the RX PHY DELAY MB valye from the configuration file
- * @param void
- * @return mb_rx_phy_delay value from the .ini file
- */
- int getPhyDelayMbRx(void)
- {
- return _config.phyDelay.mb_rx_phy_delay;
+ return _config.phy_delay;
}
/**
@@ -169,6 +152,11 @@ class GptpIniParser
return _config.syncReceiptThresh;
}
+ /**
+ * @brief Dump PHY delays to screen
+ */
+ void print_phy_delay( void );
+
private:
int _error;
gptp_cfg_t _config;
diff --git a/daemons/gptp/common/ieee1588.hpp b/daemons/gptp/common/ieee1588.hpp
index af42c243..bd95a5fa 100644
--- a/daemons/gptp/common/ieee1588.hpp
+++ b/daemons/gptp/common/ieee1588.hpp
@@ -48,6 +48,7 @@
#include <ptptypes.hpp>
#include <gptp_log.hpp>
+#include <limits.h>
#define MAX_PORTS 32 /*!< Maximum number of EtherPort instances */
@@ -108,14 +109,6 @@ typedef struct {
Event event; //!< Event enumeration
} event_descriptor_t;
-struct phy_delay
-{
- int mb_tx_phy_delay;
- int mb_rx_phy_delay;
- int gb_tx_phy_delay;
- int gb_rx_phy_delay;
-};
-
/**
* @brief Provides a generic InterfaceLabel class
*/
@@ -235,14 +228,12 @@ class ClockIdentity {
#define INVALID_TIMESTAMP_VERSION 0xFF /*!< Value defining invalid timestamp version*/
#define MAX_NANOSECONDS 1000000000 /*!< Maximum value of nanoseconds (1 second)*/
-#define MAX_TIMESTAMP_STRLEN 28 /*!< Maximum size of timestamp strlen*/
+#define MAX_TSTAMP_STRLEN 25 /*!< Maximum size of timestamp strlen*/
/**
* @brief Provides a Timestamp interface
*/
class Timestamp {
-private:
- char output_string[MAX_TIMESTAMP_STRLEN];
public:
/**
* @brief Creates a Timestamp instance
@@ -264,7 +255,7 @@ public:
* the private parameters
*/
Timestamp() {
- output_string[0] = '\0';
+ Timestamp( 0, 0, 0 );
}
uint32_t nanoseconds; //!< 32 bit nanoseconds value
uint32_t seconds_ls; //!< 32 bit seconds LSB value
@@ -274,14 +265,17 @@ public:
/**
* @brief Copies the timestamp to the internal string in the following format:
* seconds_ms seconds_ls nanoseconds
- * @return Formated string (as a char *)
+ * @return STL string containing timestamp
*/
- char *toString() {
+ std::string toString() const
+ {
+ char output_string[MAX_TSTAMP_STRLEN+1];
+
PLAT_snprintf
- ( output_string, 28, "%hu %u %u", seconds_ms, seconds_ls
- ,
- nanoseconds );
- return output_string;
+ ( output_string, MAX_TSTAMP_STRLEN+1, "%hu %u.%09u",
+ seconds_ms, seconds_ls, nanoseconds );
+
+ return std::string( output_string );
}
/**
@@ -458,213 +452,6 @@ static inline void TIMESTAMP_ADD_NS( Timestamp &ts, uint64_t ns ) {
ts.nanoseconds = (uint32_t)nanos;
}
-#define HWTIMESTAMPER_EXTENDED_MESSAGE_SIZE 4096 /*!< Maximum size of HWTimestamper extended message */
-
-/**
- * @brief Provides a generic interface for hardware timestamping
- */
-class HWTimestamper {
-
-protected:
- uint8_t version; //!< HWTimestamper version
- struct phy_delay delay;
-public:
- /**
- * @brief Initializes the hardware timestamp unit
- * @param iface_label [in] Interface label
- * @param iface [in] Network interface
- * @return true
- */
- virtual bool HWTimestamper_init
- ( InterfaceLabel *iface_label, OSNetworkInterface *iface )
- { return true; }
-
- /**
- * @brief Reset the hardware timestamp unit
- * @return void
- */
- virtual void HWTimestamper_reset(void) {
- }
-
- /**
- * @brief This method is called before the object is de-allocated.
- * @return void
- */
- virtual void HWTimestamper_final(void) {
- }
-
- /**
- * @brief Adjusts the hardware clock frequency
- * @param frequency_offset Frequency offset
- * @return false
- */
- virtual bool HWTimestamper_adjclockrate
- ( float frequency_offset ) const
- { return false; }
-
- /**
- * @brief Adjusts the hardware clock phase
- * @param phase_adjust Phase offset
- * @return false
- */
- virtual bool HWTimestamper_adjclockphase( int64_t phase_adjust )
- { return false; }
-
- /**
- * @brief Get the cross timestamping information.
- * The gPTP subsystem uses these samples to calculate
- * ratios which can be used to translate or extrapolate
- * one clock into another clock reference. The gPTP service
- * uses these supplied cross timestamps to perform internal
- * rate estimation and conversion functions.
- * @param system_time [out] System time
- * @param device_time [out] Device time
- * @param local_clock [out] Local clock
- * @param nominal_clock_rate [out] Nominal clock rate
- * @return True in case of success. FALSE in case of error
- */
- virtual bool HWTimestamper_gettime(Timestamp * system_time,
- Timestamp * device_time,
- uint32_t * local_clock,
- uint32_t * nominal_clock_rate) const = 0;
-
- /**
- * @brief Gets the tx timestamp from hardware
- * @param identity PTP port identity
- * @param PTPMessageId Message ID
- * @param timestamp [out] Timestamp value
- * @param clock_value [out] Clock value
- * @param last Signalizes that it is the last timestamp to get. When TRUE, releases the lock when its done.
- * @return GPTP_EC_SUCCESS if no error, GPTP_EC_FAILURE if error and GPTP_EC_EAGAIN to try again.
- */
- virtual int HWTimestamper_txtimestamp(PortIdentity * identity,
- PTPMessageId messageId,
- Timestamp & timestamp,
- unsigned &clock_value,
- bool last) = 0;
-
- /**
- * @brief Get rx timestamp
- * @param identity PTP port identity
- * @param messageId Message ID
- * @param timestamp [out] Timestamp value
- * @param clock_value [out] Clock value
- * @param last Signalizes that it is the last timestamp to get. When TRUE, releases the lock when its done.
- * @return GPTP_EC_SUCCESS if no error, GPTP_EC_FAILURE if error and GPTP_EC_EAGAIN to try again.
- */
- virtual int HWTimestamper_rxtimestamp(PortIdentity * identity,
- PTPMessageId messageId,
- Timestamp & timestamp,
- unsigned &clock_value,
- bool last) = 0;
-
- /**
- * @brief Get external clock offset
- * @param local_time [inout] Local time
- * @param clk_offset [inout] clock offset
- * @param ppt_freq_offset [inout] Frequency offset in ppts
- * @return false
- * @todo This code should be removed. It was a hack to get a specific board
- * working.
- */
- virtual bool HWTimestamper_get_extclk_offset(Timestamp * local_time,
- int64_t * clk_offset,
- int32_t *
- ppt_freq_offset) {
- return false;
- }
-
- /**
- * @brief Gets a string with the error from the hardware timestamp block
- * @param msg [out] String error
- * @return void
- * @todo There is no current implementation for this method.
- */
- virtual void HWTimestamper_get_extderror(char *msg) const
- {
- *msg = '\0';
- }
-
- /**
- * @brief Starts the PPS (pulse per second) interface
- * @return false
- */
- virtual bool HWTimestamper_PPS_start() { return false; };
-
- /**
- * @brief Stops the PPS (pulse per second) interface
- * @return true
- */
- virtual bool HWTimestamper_PPS_stop() { return true; };
-
- /**
- * @brief Gets the HWTimestamper version
- * @return version (signed integer)
- */
- int getVersion() const
- {
- return version;
- }
- /**
- * @brief Initializes the PHY delay for TX and RX
- * @param [input] mb_tx_phy_delay, mb_rx_phy_delay, gb_tx_phy_delay, gb_rx_phy_delay
- * @return 0
- **/
-
- int init_phy_delay(int phy_delay[4])
- {
- delay.gb_tx_phy_delay = phy_delay[0];
- delay.gb_rx_phy_delay = phy_delay[1];
- delay.mb_tx_phy_delay = phy_delay[2];
- delay.mb_rx_phy_delay = phy_delay[3];
-
-
- return 0;
- }
-
- /**
- * @brief Returns the the PHY delay for TX and RX
- * @param [input] struct phy_delay pointer
- * @return 0
- **/
-
- int get_phy_delay (struct phy_delay *get_delay) const
- {
- get_delay->mb_tx_phy_delay = delay.mb_tx_phy_delay;
- get_delay->mb_rx_phy_delay = delay.mb_rx_phy_delay;
- get_delay->gb_tx_phy_delay = delay.gb_tx_phy_delay;
- get_delay->gb_rx_phy_delay = delay.gb_rx_phy_delay;
-
- return 0;
- }
-
- /**
- * @brief Sets the the PHY delay for TX and RX
- * @param [input] struct phy_delay pointer
- * @return 0
- **/
-
- int set_phy_delay(struct phy_delay *set_delay)
- {
- delay.mb_tx_phy_delay = set_delay->mb_tx_phy_delay;
- delay.mb_rx_phy_delay = set_delay->mb_rx_phy_delay;
- delay.gb_tx_phy_delay = set_delay->gb_tx_phy_delay;
- delay.gb_rx_phy_delay = set_delay->gb_rx_phy_delay;
-
- return 0;
- }
-
- /**
- * @brief Default constructor. Sets version to zero.
- */
- HWTimestamper() { version = 0; }
-
- /**
- * @brief Deletes HWtimestamper object
- */
- virtual ~HWTimestamper() { }
-};
-
/**
* @brief Builds a PTP message
* @param buf [in] message buffer to send
diff --git a/daemons/gptp/common/ieee1588clock.cpp b/daemons/gptp/common/ieee1588clock.cpp
index dbae6e16..03f16129 100644
--- a/daemons/gptp/common/ieee1588clock.cpp
+++ b/daemons/gptp/common/ieee1588clock.cpp
@@ -79,8 +79,8 @@ void ClockIdentity::set(LinkLayerAddress * addr)
IEEE1588Clock::IEEE1588Clock
( bool forceOrdinarySlave, bool syntonize, uint8_t priority1,
- HWTimestamper *timestamper, OSTimerQueueFactory *timerq_factory,
- OS_IPC *ipc, OSLockFactory *lock_factory )
+ OSTimerQueueFactory *timerq_factory, OS_IPC *ipc,
+ OSLockFactory *lock_factory )
{
this->priority1 = priority1;
priority2 = 248;
@@ -106,7 +106,6 @@ IEEE1588Clock::IEEE1588Clock
_master_local_freq_offset_init = false;
_local_system_freq_offset_init = false;
- _timestamper = timestamper;
this->ipc = ipc;
@@ -401,20 +400,17 @@ void IEEE1588Clock::setMasterOffset
if( _new_syntonization_set_point || _phase_error_violation > PHASE_ERROR_MAX_COUNT ) {
_new_syntonization_set_point = false;
_phase_error_violation = 0;
- if( _timestamper ) {
- /* Make sure that there are no transmit operations
- in progress */
- getTxLockAll();
- if (port->getTestMode()) {
- GPTP_LOG_STATUS("Adjust clock phase offset:%lld", -master_local_offset);
- }
- _timestamper->HWTimestamper_adjclockphase
- ( -master_local_offset );
- _master_local_freq_offset_init = false;
- restartPDelayAll();
- putTxLockAll();
- master_local_offset = 0;
+ /* Make sure that there are no transmit operations
+ in progress */
+ getTxLockAll();
+ if (port->getTestMode()) {
+ GPTP_LOG_STATUS("Adjust clock phase offset:%lld", -master_local_offset);
}
+ port->adjustClockPhase( -master_local_offset );
+ _master_local_freq_offset_init = false;
+ restartPDelayAll();
+ putTxLockAll();
+ master_local_offset = 0;
}
// Adjust for frequency offset
@@ -432,13 +428,11 @@ void IEEE1588Clock::setMasterOffset
if( _ppm < LOWER_FREQ_LIMIT ) _ppm = LOWER_FREQ_LIMIT;
if( _ppm > UPPER_FREQ_LIMIT ) _ppm = UPPER_FREQ_LIMIT;
- if( _timestamper ) {
- if (port->getTestMode()) {
- GPTP_LOG_STATUS("Adjust clock rate ppm:%f", _ppm);
- }
- if( !_timestamper->HWTimestamper_adjclockrate( _ppm )) {
- GPTP_LOG_ERROR( "Failed to adjust clock rate" );
- }
+ if (port->getTestMode()) {
+ GPTP_LOG_STATUS("Adjust clock rate ppm:%f", _ppm);
+ }
+ if( !port->adjustClockRate( _ppm )) {
+ GPTP_LOG_ERROR( "Failed to adjust clock rate" );
}
}
diff --git a/daemons/gptp/common/ptp_message.cpp b/daemons/gptp/common/ptp_message.cpp
index 0e3914fc..9219338b 100644
--- a/daemons/gptp/common/ptp_message.cpp
+++ b/daemons/gptp/common/ptp_message.cpp
@@ -36,6 +36,7 @@
#include <avbts_message.hpp>
#include <ether_port.hpp>
#include <avbts_ostimer.hpp>
+#include <ether_tstamper.hpp>
#include <stdio.h>
#include <string.h>
@@ -139,8 +140,8 @@ PTPMessageCommon *buildPTPMessage
req *= 2;
}
if (ts_good != GPTP_EC_SUCCESS) {
- char msg[HWTIMESTAMPER_EXTENDED_MESSAGE_SIZE];
- port->getExtendedError(msg);
+ char err_msg[HWTIMESTAMPER_EXTENDED_MESSAGE_SIZE];
+ port->getExtendedError(err_msg);
GPTP_LOG_ERROR
("*** Received an event packet but cannot retrieve timestamp, discarding. messageType=%u,error=%d\n%s",
messageType, ts_good, msg);
@@ -542,6 +543,50 @@ abort:
return NULL;
}
+bool PTPMessageCommon::getTxTimestamp( EtherPort *port, uint32_t link_speed )
+{
+ OSTimer *timer = port->getTimerFactory()->createTimer();
+ int ts_good;
+ Timestamp tx_timestamp;
+ uint32_t unused;
+ unsigned req = TX_TIMEOUT_BASE;
+ int iter = TX_TIMEOUT_ITER;
+
+ ts_good = port->getTxTimestamp
+ ( this, tx_timestamp, unused, false );
+ while( ts_good != GPTP_EC_SUCCESS && iter-- != 0 )
+ {
+ timer->sleep(req);
+ if (ts_good != GPTP_EC_EAGAIN && iter < 1)
+ GPTP_LOG_ERROR(
+ "Error (TX) timestamping PDelay request "
+ "(Retrying-%d), error=%d", iter, ts_good);
+ ts_good = port->getTxTimestamp
+ ( this, tx_timestamp, unused , iter == 0 );
+ req *= 2;
+ }
+
+ if( ts_good == GPTP_EC_SUCCESS )
+ {
+ Timestamp phy_compensation = port->getTxPhyDelay( link_speed );
+ GPTP_LOG_DEBUG( "TX PHY compensation: %s sec",
+ phy_compensation.toString().c_str() );
+ phy_compensation._version = tx_timestamp._version;
+ _timestamp = tx_timestamp + phy_compensation;
+ } else
+ {
+ char msg[HWTIMESTAMPER_EXTENDED_MESSAGE_SIZE];
+ port->getExtendedError(msg);
+ GPTP_LOG_ERROR(
+ "Error (TX) timestamping PDelay request, error=%d\t%s",
+ ts_good, msg);
+ _timestamp = INVALID_TIMESTAMP;
+ }
+
+ delete timer;
+ return ts_good == GPTP_EC_SUCCESS;
+}
+
void PTPMessageCommon::processMessage( EtherPort *port )
{
_gc = true;
@@ -681,13 +726,15 @@ PTPMessageSync::PTPMessageSync( EtherPort *port ) :
return;
}
-void PTPMessageSync::sendPort
+bool PTPMessageSync::sendPort
( EtherPort *port, PortIdentity *destIdentity )
{
uint8_t buf_t[256];
uint8_t *buf_ptr = buf_t + port->getPayloadOffset();
unsigned char tspec_msg_t = 0x0;
Timestamp originTimestamp_BE;
+ uint32_t link_speed;
+
memset(buf_t, 0, 256);
// Create packet in buf
// Copy in common header
@@ -711,10 +758,12 @@ void PTPMessageSync::sendPort
&(originTimestamp_BE.nanoseconds),
sizeof(originTimestamp.nanoseconds));
- port->sendEventPort(PTP_ETHERTYPE, buf_t, messageLength, MCAST_OTHER, destIdentity);
+ port->sendEventPort
+ ( PTP_ETHERTYPE, buf_t, messageLength, MCAST_OTHER,
+ destIdentity, &link_speed );
port->incCounter_ieee8021AsPortStatTxSyncCount();
- return;
+ return getTxTimestamp( port, link_speed );
}
PTPMessageAnnounce::PTPMessageAnnounce( CommonPort *port ) :
@@ -743,7 +792,7 @@ PTPMessageAnnounce::PTPMessageAnnounce( CommonPort *port ) :
return;
}
-void PTPMessageAnnounce::sendPort
+bool PTPMessageAnnounce::sendPort
( CommonPort *port, PortIdentity *destIdentity )
{
uint8_t buf_t[256];
@@ -786,7 +835,7 @@ void PTPMessageAnnounce::sendPort
port->sendGeneralPort(PTP_ETHERTYPE, buf_t, messageLength, MCAST_OTHER, destIdentity);
port->incCounter_ieee8021AsPortStatTxAnnounce();
- return;
+ return true;
}
void PTPMessageAnnounce::processMessage( EtherPort *port )
@@ -874,7 +923,7 @@ PTPMessageFollowUp::PTPMessageFollowUp( EtherPort *port ) :
return;
}
-void PTPMessageFollowUp::sendPort
+bool PTPMessageFollowUp::sendPort
( EtherPort *port, PortIdentity *destIdentity )
{
uint8_t buf_t[256];
@@ -931,7 +980,7 @@ void PTPMessageFollowUp::sendPort
port->incCounter_ieee8021AsPortStatTxFollowUpCount();
- return;
+ return true;
}
void PTPMessageFollowUp::processMessage( EtherPort *port )
@@ -1130,12 +1179,6 @@ void PTPMessagePathDelayReq::processMessage( EtherPort *port )
PortIdentity resp_id;
PTPMessagePathDelayRespFollowUp *resp_fwup;
- int ts_good;
- Timestamp resp_timestamp;
- unsigned resp_timestamp_counter_value;
- unsigned req = TX_TIMEOUT_BASE;
- int iter = TX_TIMEOUT_ITER;
-
if (port->getPortState() == PTP_DISABLED) {
// Do nothing all messages should be ignored when in this state
goto done;
@@ -1166,41 +1209,15 @@ void PTPMessagePathDelayReq::processMessage( EtherPort *port )
this->getPortIdentity(&requestingPortIdentity_p);
resp->setRequestingPortIdentity(&requestingPortIdentity_p);
resp->setRequestReceiptTimestamp(_timestamp);
+
port->getTxLock();
resp->sendPort(port, sourcePortIdentity);
-
GPTP_LOG_DEBUG("*** Sent PDelay Response message");
-
- GPTP_LOG_VERBOSE("Start TS Read");
- ts_good = port->getTxTimestamp
- (resp, resp_timestamp, resp_timestamp_counter_value, false);
-
- GPTP_LOG_VERBOSE("Done TS Read");
-
- while (ts_good != GPTP_EC_SUCCESS && iter-- != 0) {
- timer->sleep(req);
- if (ts_good == GPTP_EC_EAGAIN && iter < 1)
- GPTP_LOG_ERROR( "Error (TX) timestamping PDelay Response "
- "(Retrying-%d), error=%d", iter, ts_good);
- ts_good = port->getTxTimestamp
- (resp, resp_timestamp, resp_timestamp_counter_value, iter == 0);
- req *= 2;
- }
port->putTxLock();
- if (ts_good != GPTP_EC_SUCCESS) {
- char msg[HWTIMESTAMPER_EXTENDED_MESSAGE_SIZE];
- port->getExtendedError(msg);
- GPTP_LOG_ERROR
- ( "Error (TX) timestamping PDelay Response, error=%d\t%s",
- ts_good, msg);
- delete resp;
- goto done;
- }
-
- if( resp_timestamp._version != _timestamp._version ) {
+ if( resp->getTimestamp()._version != _timestamp._version ) {
GPTP_LOG_ERROR("TX timestamp version mismatch: %u/%u",
- resp_timestamp._version, _timestamp._version);
+ resp->getTimestamp()._version, _timestamp._version);
#if 0 // discarding the request could lead to the peer setting the link to non-asCapable
delete resp;
goto done;
@@ -1212,16 +1229,17 @@ void PTPMessagePathDelayReq::processMessage( EtherPort *port )
resp_fwup->setPortIdentity(&resp_fwup_id);
resp_fwup->setSequenceId(sequenceId);
resp_fwup->setRequestingPortIdentity(sourcePortIdentity);
- resp_fwup->setResponseOriginTimestamp(resp_timestamp);
+ resp_fwup->setResponseOriginTimestamp(resp->getTimestamp());
long long turnaround;
- turnaround =
- (resp_timestamp.seconds_ls - _timestamp.seconds_ls) * 1000000000LL;
+ turnaround = (resp->getTimestamp().seconds_ls - _timestamp.seconds_ls)
+ * 1000000000LL;
- GPTP_LOG_VERBOSE("Response Depart(sec): %u", resp_timestamp.seconds_ls);
+ GPTP_LOG_VERBOSE("Response Depart(sec): %u",
+ resp->getTimestamp().seconds_ls);
GPTP_LOG_VERBOSE("Request Arrival(sec): %u", _timestamp.seconds_ls);
GPTP_LOG_VERBOSE("#1 Correction Field: %Ld", turnaround);
- turnaround += resp_timestamp.nanoseconds;
+ turnaround += resp->getTimestamp().nanoseconds;
GPTP_LOG_VERBOSE("#2 Correction Field: %Ld", turnaround);
@@ -1243,11 +1261,13 @@ done:
return;
}
-void PTPMessagePathDelayReq::sendPort
+bool PTPMessagePathDelayReq::sendPort
( EtherPort *port, PortIdentity *destIdentity )
{
+ uint32_t link_speed;
+
if(port->pdelayHalted())
- return;
+ return false;
uint8_t buf_t[256];
uint8_t *buf_ptr = buf_t + port->getPayloadOffset();
@@ -1258,9 +1278,12 @@ void PTPMessagePathDelayReq::sendPort
messageLength = PTP_COMMON_HDR_LENGTH + PTP_PDELAY_REQ_LENGTH;
tspec_msg_t |= messageType & 0xF;
buildCommonHeader(buf_ptr);
- port->sendEventPort(PTP_ETHERTYPE, buf_t, messageLength, MCAST_PDELAY, destIdentity);
+ port->sendEventPort
+ ( PTP_ETHERTYPE, buf_t, messageLength, MCAST_PDELAY,
+ destIdentity, &link_speed );
port->incCounter_ieee8021AsPortStatTxPdelayRequest();
- return;
+
+ return getTxTimestamp( port, link_speed );
}
PTPMessagePathDelayResp::PTPMessagePathDelayResp
@@ -1361,13 +1384,15 @@ bypass_verify_duplicate:
return;
}
-void PTPMessagePathDelayResp::sendPort
+bool PTPMessagePathDelayResp::sendPort
( EtherPort *port, PortIdentity *destIdentity )
{
uint8_t buf_t[256];
uint8_t *buf_ptr = buf_t + port->getPayloadOffset();
unsigned char tspec_msg_t = 0;
Timestamp requestReceiptTimestamp_BE;
+ uint32_t link_speed;
+
memset(buf_t, 0, 256);
// Create packet in buf
// Copy in common header
@@ -1403,9 +1428,12 @@ void PTPMessagePathDelayResp::sendPort
requestReceiptTimestamp.seconds_ls,
requestReceiptTimestamp.nanoseconds);
- port->sendEventPort(PTP_ETHERTYPE, buf_t, messageLength, MCAST_PDELAY, destIdentity);
+ port->sendEventPort
+ ( PTP_ETHERTYPE, buf_t, messageLength, MCAST_PDELAY,
+ destIdentity, &link_speed );
port->incCounter_ieee8021AsPortStatTxPdelayResponse();
- return;
+
+ return getTxTimestamp( port, link_speed );
}
void PTPMessagePathDelayResp::setRequestingPortIdentity
@@ -1633,6 +1661,7 @@ void PTPMessagePathDelayRespFollowUp::processMessage
/* Subtract turn-around time from link delay after rate adjustment */
link_delay -= turn_around;
link_delay /= 2;
+ GPTP_LOG_DEBUG( "Link delay: %ld ns", link_delay );
{
uint64_t mine_elapsed;
@@ -1682,7 +1711,7 @@ void PTPMessagePathDelayRespFollowUp::processMessage
return;
}
-void PTPMessagePathDelayRespFollowUp::sendPort
+bool PTPMessagePathDelayRespFollowUp::sendPort
( EtherPort *port, PortIdentity *destIdentity )
{
uint8_t buf_t[256];
@@ -1729,7 +1758,8 @@ void PTPMessagePathDelayRespFollowUp::sendPort
port->sendGeneralPort(PTP_ETHERTYPE, buf_t, messageLength, MCAST_PDELAY, destIdentity);
port->incCounter_ieee8021AsPortStatTxPdelayResponseFollowUp();
- return;
+
+ return true;
}
void PTPMessagePathDelayRespFollowUp::setRequestingPortIdentity
@@ -1767,7 +1797,7 @@ void PTPMessageSignalling::setintervals(int8_t linkDelayInterval, int8_t timeSyn
tlv.setAnnounceInterval(announceInterval);
}
-void PTPMessageSignalling::sendPort
+bool PTPMessageSignalling::sendPort
( EtherPort *port, PortIdentity *destIdentity )
{
uint8_t buf_t[256];
@@ -1787,6 +1817,8 @@ void PTPMessageSignalling::sendPort
tlv.toByteString(buf_ptr + PTP_COMMON_HDR_LENGTH + PTP_SIGNALLING_LENGTH);
port->sendGeneralPort(PTP_ETHERTYPE, buf_t, messageLength, MCAST_OTHER, destIdentity);
+
+ return true;
}
void PTPMessageSignalling::processMessage( EtherPort *port )
diff --git a/daemons/gptp/gptp_cfg.ini b/daemons/gptp/gptp_cfg.ini
index 35a00848..ee593e9e 100644
--- a/daemons/gptp/gptp_cfg.ini
+++ b/daemons/gptp/gptp_cfg.ini
@@ -31,19 +31,32 @@ syncReceiptThresh = 8
[eth]
+# Older deprecated format
# PHY delay GB TX in nanoseconds
# The default for I210 is 184
-phy_delay_gb_tx = 184
+#phy_delay_gb_tx = 184
+# Older deprecated format
# PHY delay GB RX in nanoseconds
-# The default for I210 is 382
-phy_delay_gb_rx = 382
+# The default for I210 is 184
+#phy_delay_gb_rx = 382
-# PHY delay MB TX in nanoseconds
+# Older deprecated format
+# PHY delay 100 MB TX in nanoseconds
# The default for I210 is 1044
-phy_delay_mb_tx = 1044
+#phy_delay_mb_tx = 1044
-# PHY delay MB RX in nanoseconds
+# Older deprecated format
+# PHY delay 100 MB RX in nanoseconds
# The default for I210 is 2133
-phy_delay_mb_rx = 2133
+#phy_delay_mb_rx = 2133
+
+# Newer flexible format
+# PHY delay GB RX/TX in nanoseconds
+# Link speed may be specified numerically or by name
+#phy_delay = 1000000 184 382
+phy_delay = LINKSPEED_1G 184 382
+
+# PHY delay 100 MB RX/TX in nanoseconds
+phy_delay = LINKSPEED_100MB 1044 2133
diff --git a/daemons/gptp/linux/src/daemon_cl.cpp b/daemons/gptp/linux/src/daemon_cl.cpp
index 129fbd6b..86806783 100644
--- a/daemons/gptp/linux/src/daemon_cl.cpp
+++ b/daemons/gptp/linux/src/daemon_cl.cpp
@@ -171,7 +171,7 @@ int main(int argc, char **argv)
GPTP_LOG_ERROR("Watchdog handler setup error");
return -1;
}
- int phy_delay[4]={0,0,0,0};
+ phy_delay_map_t ether_phy_delay;
bool input_delay=false;
portInit.clock = NULL;
@@ -190,6 +190,10 @@ int main(int argc, char **argv)
portInit.thread_factory = NULL;
portInit.timer_factory = NULL;
portInit.lock_factory = NULL;
+ portInit.syncReceiptThreshold =
+ CommonPort::DEFAULT_SYNC_RECEIPT_THRESH;
+ portInit.neighborPropDelayThreshold =
+ CommonPort::NEIGHBOR_PROP_DELAY_THRESH;
LinuxNetworkInterfaceFactory *default_factory =
new LinuxNetworkInterfaceFactory;
@@ -267,6 +271,7 @@ int main(int argc, char **argv)
}
}
else if (strcmp(argv[i] + 1, "D") == 0) {
+ int phy_delay[4];
input_delay=true;
int delay_count=0;
char *cli_inp_delay = strtok(argv[i+1],",");
@@ -290,6 +295,10 @@ int main(int argc, char **argv)
GPTP_LOG_UNREGISTER();
return 0;
}
+ ether_phy_delay[LINKSPEED_1G].set_delay
+ ( phy_delay[0], phy_delay[1] );
+ ether_phy_delay[LINKSPEED_100MB].set_delay
+ ( phy_delay[2], phy_delay[3] );
}
else if (strcmp(argv[i] + 1, "V") == 0) {
portInit.automotive_profile = true;
@@ -326,11 +335,12 @@ int main(int argc, char **argv)
if (!input_delay)
{
- phy_delay[0] = PHY_DELAY_GB_TX_I20;
- phy_delay[1] = PHY_DELAY_GB_RX_I20;
- phy_delay[2] = PHY_DELAY_MB_TX_I20;
- phy_delay[3] = PHY_DELAY_MB_RX_I20;
+ ether_phy_delay[LINKSPEED_1G].set_delay
+ ( PHY_DELAY_GB_TX_I20, PHY_DELAY_GB_RX_I20 );
+ ether_phy_delay[LINKSPEED_100MB].set_delay
+ ( PHY_DELAY_MB_TX_I20, PHY_DELAY_MB_RX_I20 );
}
+ portInit.phy_delay = &ether_phy_delay;
if( !ipc->init( ipc_arg ) ) {
delete ipc;
@@ -348,9 +358,9 @@ int main(int argc, char **argv)
}
#ifdef ARCH_INTELCE
- HWTimestamper *timestamper = new LinuxTimestamperIntelCE();
+ EtherTimestamper *timestamper = new LinuxTimestamperIntelCE();
#else
- HWTimestamper *timestamper = new LinuxTimestamperGeneric();
+ EtherTimestamper *timestamper = new LinuxTimestamperGeneric();
#endif
sigemptyset(&set);
@@ -364,8 +374,9 @@ int main(int argc, char **argv)
return -1;
}
- pClock = new IEEE1588Clock( false, syntonize, priority1, timestamper,
- timerq_factory, ipc, lock_factory );
+ pClock = new IEEE1588Clock
+ ( false, syntonize, priority1, timerq_factory, ipc,
+ lock_factory );
if( restoredataptr != NULL ) {
if( !restorefailed )
@@ -385,8 +396,6 @@ int main(int argc, char **argv)
portInit.timer_factory = timer_factory;
portInit.lock_factory = lock_factory;
- pPort = new EtherPort(&portInit);
-
if(use_config_file)
{
GptpIniParser iniParser(config_file_path);
@@ -399,35 +408,33 @@ int main(int argc, char **argv)
GPTP_LOG_INFO("priority1 = %d", iniParser.getPriority1());
GPTP_LOG_INFO("announceReceiptTimeout: %d", iniParser.getAnnounceReceiptTimeout());
GPTP_LOG_INFO("syncReceiptTimeout: %d", iniParser.getSyncReceiptTimeout());
- GPTP_LOG_INFO("phy_delay_gb_tx: %d", iniParser.getPhyDelayGbTx());
- GPTP_LOG_INFO("phy_delay_gb_rx: %d", iniParser.getPhyDelayGbRx());
- GPTP_LOG_INFO("phy_delay_mb_tx: %d", iniParser.getPhyDelayMbTx());
- GPTP_LOG_INFO("phy_delay_mb_rx: %d", iniParser.getPhyDelayMbRx());
+ iniParser.print_phy_delay();
GPTP_LOG_INFO("neighborPropDelayThresh: %ld", iniParser.getNeighborPropDelayThresh());
GPTP_LOG_INFO("syncReceiptThreshold: %d", iniParser.getSyncReceiptThresh());
/* If using config file, set the neighborPropDelayThresh.
* Otherwise it will use its default value (800ns) */
- pPort->setNeighPropDelayThresh(iniParser.getNeighborPropDelayThresh());
+ portInit.neighborPropDelayThreshold =
+ iniParser.getNeighborPropDelayThresh();
/* If using config file, set the syncReceiptThreshold, otherwise
* it will use the default value (SYNC_RECEIPT_THRESH)
*/
- pPort->setSyncReceiptThresh(iniParser.getSyncReceiptThresh());
+ portInit.syncReceiptThreshold =
+ iniParser.getSyncReceiptThresh();
/*Only overwrites phy_delay default values if not input_delay switch enabled*/
if(!input_delay)
{
- phy_delay[0] = iniParser.getPhyDelayGbTx();
- phy_delay[1] = iniParser.getPhyDelayGbRx();
- phy_delay[2] = iniParser.getPhyDelayMbTx();
- phy_delay[3] = iniParser.getPhyDelayMbRx();
+ ether_phy_delay = iniParser.getPhyDelay();
}
}
}
- if (!pPort->init_port(phy_delay)) {
+ pPort = new EtherPort(&portInit);
+
+ if (!pPort->init_port()) {
GPTP_LOG_ERROR("failed to initialize port");
GPTP_LOG_UNREGISTER();
return -1;
diff --git a/daemons/gptp/linux/src/linux_hal_common.cpp b/daemons/gptp/linux/src/linux_hal_common.cpp
index 19e13c5b..1000a265 100644
--- a/daemons/gptp/linux/src/linux_hal_common.cpp
+++ b/daemons/gptp/linux/src/linux_hal_common.cpp
@@ -59,6 +59,8 @@
#include <netinet/in.h>
#include <linux/netlink.h>
#include <linux/rtnetlink.h>
+#include <linux/sockios.h>
+#include <gptp_cfg.hpp>
Timestamp tsToTimestamp(struct timespec *ts)
{
@@ -255,6 +257,55 @@ static void x_initLinkUpStatus( EtherPort *pPort, int ifindex )
close(inetSocket);
}
+
+bool LinuxNetworkInterface::getLinkSpeed( int sd, uint32_t *speed )
+{
+ struct ifreq ifr;
+ struct ethtool_cmd edata;
+
+ ifr.ifr_ifindex = ifindex;
+ if( ioctl( sd, SIOCGIFNAME, &ifr ) == -1 )
+ {
+ GPTP_LOG_ERROR
+ ( "%s: SIOCGIFNAME failed: %s", __PRETTY_FUNCTION__,
+ strerror( errno ));
+ return false;
+ }
+
+ ifr.ifr_data = (char *) &edata;
+ edata.cmd = ETHTOOL_GSET;
+ if( ioctl( sd, SIOCETHTOOL, &ifr ) == -1 )
+ {
+ GPTP_LOG_ERROR
+ ( "%s: SIOCETHTOOL failed: %s", __PRETTY_FUNCTION__,
+ strerror( errno ));
+ return false;
+ }
+
+ switch (ethtool_cmd_speed(&edata))
+ {
+ default:
+ GPTP_LOG_ERROR( "%s: Unknown/Unsupported Speed!",
+ __PRETTY_FUNCTION__ );
+ return false;
+ case SPEED_100:
+ *speed = LINKSPEED_100MB;
+ break;
+ case SPEED_1000:
+ *speed = LINKSPEED_1G;
+ break;
+ case SPEED_2500:
+ *speed = LINKSPEED_2_5G;
+ break;
+ case SPEED_10000:
+ *speed = LINKSPEED_10G;
+ break;
+ }
+ GPTP_LOG_STATUS( "Link Speed: %d kb/sec", *speed );
+
+ return true;
+}
+
void LinuxNetworkInterface::watchNetLink( CommonPort *iPort )
{
fd_set netLinkFD;
@@ -287,6 +338,15 @@ void LinuxNetworkInterface::watchNetLink( CommonPort *iPort )
}
x_initLinkUpStatus(pPort, ifindex);
+ if( pPort->getLinkUpState() )
+ {
+ uint32_t link_speed;
+ getLinkSpeed( netLinkSocket, &link_speed );
+ pPort->setLinkSpeed((int32_t) link_speed );
+ } else
+ {
+ pPort->setLinkSpeed( INVALID_LINKSPEED );
+ }
while (1) {
FD_ZERO(&netLinkFD);
@@ -298,7 +358,21 @@ void LinuxNetworkInterface::watchNetLink( CommonPort *iPort )
if (retval == -1)
; // Error on select. We will ignore and keep going
else if (retval) {
+ bool prev_link_up = pPort->getLinkUpState();
x_readEvent(netLinkSocket, pPort, ifindex);
+
+ // Don't do anything else if link state is the same
+ if( prev_link_up == pPort->getLinkUpState() )
+ continue;
+ if( pPort->getLinkUpState() )
+ {
+ uint32_t link_speed;
+ getLinkSpeed( netLinkSocket, &link_speed );
+ pPort->setLinkSpeed((int32_t) link_speed );
+ } else
+ {
+ pPort->setLinkSpeed( INVALID_LINKSPEED );
+ }
}
else {
; // Would be timeout but Won't happen because we wait forever
@@ -929,7 +1003,7 @@ void LinuxSharedMemoryIPC::stop() {
bool LinuxNetworkInterfaceFactory::createInterface
( OSNetworkInterface **net_iface, InterfaceLabel *label,
- HWTimestamper *timestamper ) {
+ CommonTimestamper *timestamper ) {
struct ifreq device;
int err;
struct sockaddr_ll ifsock_addr;
diff --git a/daemons/gptp/linux/src/linux_hal_common.hpp b/daemons/gptp/linux/src/linux_hal_common.hpp
index 4fcbd68b..28332f01 100644
--- a/daemons/gptp/linux/src/linux_hal_common.hpp
+++ b/daemons/gptp/linux/src/linux_hal_common.hpp
@@ -44,6 +44,8 @@
#include "avbts_osthread.hpp"
#include "avbts_osipc.hpp"
#include "ieee1588.hpp"
+#include <ether_tstamper.hpp>
+#include <linux/ethtool.h>
#include <list>
@@ -123,7 +125,7 @@ private:
* @brief LinuxTimestamper: Provides a generic hardware
* timestamp interface for linux based systems.
*/
-class LinuxTimestamper : public HWTimestamper {
+class LinuxTimestamper : public EtherTimestamper {
public:
/**
* @brief Destructor
@@ -177,7 +179,7 @@ public:
* an error on the transmit side, net_fatal if error on reception
*/
virtual net_result nrecv
- ( LinkLayerAddress *addr, uint8_t *payload, size_t &length, struct phy_delay *delay );
+ ( LinkLayerAddress *addr, uint8_t *payload, size_t &length );
/**
* @brief Disables rx socket descriptor rx queue
@@ -201,6 +203,15 @@ public:
}
/**
+ * @brief Get speed of network link
+ *
+ * @param [in] sd Open socket descriptor
+ * @param [out] speed Link speed in kb/sec
+ * @return false on error
+ */
+ bool getLinkSpeed( int sd, uint32_t *speed );
+
+ /**
* @brief Watch for net link changes.
*/
virtual void watchNetLink( CommonPort *pPort );
@@ -573,7 +584,7 @@ public:
*/
virtual bool createInterface
( OSNetworkInterface **net_iface, InterfaceLabel *label,
- HWTimestamper *timestamper );
+ CommonTimestamper *timestamper );
};
/**
diff --git a/daemons/gptp/linux/src/linux_hal_generic.cpp b/daemons/gptp/linux/src/linux_hal_generic.cpp
index 4a3d187f..b658b0e9 100644
--- a/daemons/gptp/linux/src/linux_hal_generic.cpp
+++ b/daemons/gptp/linux/src/linux_hal_generic.cpp
@@ -52,7 +52,8 @@
#define RX_PHY_TIME 382
net_result LinuxNetworkInterface::nrecv
-( LinkLayerAddress *addr, uint8_t *payload, size_t &length,struct phy_delay *delay ) {
+( LinkLayerAddress *addr, uint8_t *payload, size_t &length )
+{
fd_set readfds;
int err;
struct msghdr msg;
@@ -136,13 +137,11 @@ net_result LinuxNetworkInterface::nrecv
if
( cmsg->cmsg_level == SOL_SOCKET &&
cmsg->cmsg_type == SO_TIMESTAMPING ) {
- Timestamp latency( delay->gb_rx_phy_delay, 0, 0 );
struct timespec *ts_device, *ts_system;
Timestamp device, system;
ts_system = ((struct timespec *) CMSG_DATA(cmsg)) + 1;
system = tsToTimestamp( ts_system );
ts_device = ts_system + 1; device = tsToTimestamp( ts_device );
- device = device - latency;
gtimestamper->pushRXTimestamp( &device );
break;
}
@@ -278,7 +277,8 @@ void LinuxTimestamperGeneric::HWTimestamper_reset()
int LinuxTimestamperGeneric::HWTimestamper_txtimestamp
( PortIdentity *identity, PTPMessageId messageId, Timestamp &timestamp,
- unsigned &clock_value, bool last ) {
+ unsigned &clock_value, bool last )
+{
int err;
int ret = GPTP_EC_EAGAIN;
struct msghdr msg;
@@ -289,10 +289,7 @@ int LinuxTimestamperGeneric::HWTimestamper_txtimestamp
struct cmsghdr cm;
char control[256];
} control;
- struct phy_delay delay_val;
- get_phy_delay (&delay_val);//gets the phy delay
- Timestamp latency( delay_val.gb_tx_phy_delay, 0, 0 );
if( sd == -1 ) return -1;
memset( &msg, 0, sizeof( msg ));
@@ -331,7 +328,6 @@ int LinuxTimestamperGeneric::HWTimestamper_txtimestamp
system = tsToTimestamp( ts_system );
ts_device = ts_system + 1; device = tsToTimestamp( ts_device );
system._version = version;
- device = device + latency;
device._version = version;
timestamp = device;
ret = 0;
diff --git a/daemons/gptp/windows/daemon_cl/daemon_cl.cpp b/daemons/gptp/windows/daemon_cl/daemon_cl.cpp
index 5e164b0d..56aebe9b 100644
--- a/daemons/gptp/windows/daemon_cl/daemon_cl.cpp
+++ b/daemons/gptp/windows/daemon_cl/daemon_cl.cpp
@@ -31,6 +31,7 @@ POSSIBILITY OF SUCH DAMAGE.
******************************************************************************/
+#include <winsock2.h>
#include <Windows.h>
#include <winnt.h>
#include "ieee1588.hpp"
@@ -39,10 +40,19 @@ POSSIBILITY OF SUCH DAMAGE.
#include "avbts_oslock.hpp"
#include "windows_hal.hpp"
#include "avbts_message.hpp"
+#include "gptp_cfg.hpp"
#include <tchar.h>
+#include <iphlpapi.h>
+
+#define PHY_DELAY_GB_TX 7750 //1G delay
+#define PHY_DELAY_GB_RX 7750 //1G delay
+#define PHY_DELAY_MB_TX 27500 //100M delay
+#define PHY_DELAY_MB_RX 27500 //100M delay
#define MACSTR_LENGTH 17
+uint32_t findLinkSpeed(LinkLayerAddress *local_addr);
+
static bool exit_flag;
void print_usage( char *arg0 ) {
@@ -82,6 +92,13 @@ int _tmain(int argc, _TCHAR* argv[])
{
PortInit_t portInit;
+ phy_delay_map_t ether_phy_delay;
+ ether_phy_delay[LINKSPEED_1G].set
+ (PHY_DELAY_GB_TX, PHY_DELAY_GB_RX);
+ ether_phy_delay[LINKSPEED_100MB].set
+ (PHY_DELAY_MB_TX, PHY_DELAY_MB_RX);
+
+
portInit.clock = NULL;
portInit.index = 1;
portInit.timestamper = NULL;
@@ -97,6 +114,8 @@ int _tmain(int argc, _TCHAR* argv[])
portInit.thread_factory = NULL;
portInit.timer_factory = NULL;
portInit.lock_factory = NULL;
+ portInit.neighborPropDelayThreshold =
+ CommonPort::NEIGHBOR_PROP_DELAY_THRESH;
bool syntonize = false;
uint8_t priority1 = 248;
@@ -162,10 +181,12 @@ int _tmain(int argc, _TCHAR* argv[])
// Create HWTimestamper object
portInit.timestamper = new WindowsTimestamper();
// Create Clock object
- portInit.clock = new IEEE1588Clock( false, false, priority1, portInit.timestamper, timerq_factory, ipc, portInit.lock_factory ); // Do not force slave
+ portInit.clock = new IEEE1588Clock( false, false, priority1, timerq_factory, ipc, portInit.lock_factory ); // Do not force slave
// Create Port Object linked to clock and low level
+ portInit.phy_delay = &ether_phy_delay;
EtherPort *port = new EtherPort( &portInit );
- if (!port->init_port(phy_delays)) {
+ port->setLinkSpeed(findLinkSpeed(&local_addr));
+ if ( !port->init_port() ) {
printf( "Failed to initialize port\n" );
return -1;
}
@@ -184,3 +205,47 @@ int _tmain(int argc, _TCHAR* argv[])
return 0;
}
+#define WIN_LINKSPEED_MULT (1000/*1 Kbit*/)
+
+uint32_t findLinkSpeed( LinkLayerAddress *local_addr )
+{
+ ULONG ret_sz;
+ char *buffer;
+ PIP_ADAPTER_ADDRESSES pAddr;
+ ULONG err;
+ uint32_t ret;
+
+ buffer = (char *) malloc((size_t)15000);
+ ret_sz = 15000;
+ pAddr = (PIP_ADAPTER_ADDRESSES)buffer;
+ err = GetAdaptersAddresses( AF_UNSPEC, 0, NULL, pAddr, &ret_sz );
+ for (; pAddr != NULL; pAddr = pAddr->Next)
+ {
+ //fprintf(stderr, "** here : %p\n", pAddr);
+ if (pAddr->PhysicalAddressLength == ETHER_ADDR_OCTETS &&
+ *local_addr == LinkLayerAddress(pAddr->PhysicalAddress))
+ {
+ break;
+ }
+ }
+
+ if (pAddr == NULL)
+ return INVALID_LINKSPEED;
+
+ switch ( pAddr->ReceiveLinkSpeed / WIN_LINKSPEED_MULT )
+ {
+ default:
+ GPTP_LOG_ERROR("Can't find link speed, %llu", pAddr->ReceiveLinkSpeed);
+ ret = INVALID_LINKSPEED;
+ break;
+ case LINKSPEED_1G:
+ ret = LINKSPEED_1G;
+ break;
+ case LINKSPEED_100MB:
+ ret = LINKSPEED_100MB;
+ break;
+ }
+
+ delete buffer;
+ return ret;
+} \ No newline at end of file
diff --git a/daemons/gptp/windows/daemon_cl/windows_hal.cpp b/daemons/gptp/windows/daemon_cl/windows_hal.cpp
index f198bc8a..a05d473c 100644
--- a/daemons/gptp/windows/daemon_cl/windows_hal.cpp
+++ b/daemons/gptp/windows/daemon_cl/windows_hal.cpp
@@ -75,7 +75,6 @@ bool WindowsTimestamper::HWTimestamper_init( InterfaceLabel *iface_label, OSNetw
PIP_ADAPTER_INFO pAdapterInfo;
IP_ADAPTER_INFO AdapterInfo[32]; // Allocate information for up to 32 NICs
DWORD dwBufLen = sizeof(AdapterInfo); // Save memory size of buffer
- struct phy_delay delay_val;
DWORD dwStatus = GetAdaptersInfo( AdapterInfo, &dwBufLen );
if( dwStatus != ERROR_SUCCESS ) return false;
@@ -88,8 +87,6 @@ bool WindowsTimestamper::HWTimestamper_init( InterfaceLabel *iface_label, OSNetw
if( pAdapterInfo == NULL ) return false;
- get_phy_delay(&delay_val);
-
DeviceClockRateMapping *rate_map = DeviceClockRateMap;
while (rate_map->device_desc != NULL)
{
@@ -105,42 +102,6 @@ bool WindowsTimestamper::HWTimestamper_init( InterfaceLabel *iface_label, OSNetw
return false;
}
- DevicePhyDelayMapping *phy_map = DevicePhyDelayMap;
- while (phy_map->device_desc != NULL)
- {
- if (strstr(pAdapterInfo->Description, phy_map->device_desc) != NULL)
- break;
- ++phy_map;
- }
- if (phy_map->device_desc != NULL) {
- if(delay_val.gb_rx_phy_delay == -1)
- delay_val.gb_rx_phy_delay = phy_map->delay.gb_rx_phy_delay;
- if (delay_val.gb_tx_phy_delay == -1)
- delay_val.gb_tx_phy_delay = phy_map->delay.gb_tx_phy_delay;
- if (delay_val.mb_rx_phy_delay == -1)
- delay_val.mb_rx_phy_delay = phy_map->delay.mb_rx_phy_delay;
- if (delay_val.mb_tx_phy_delay == -1)
- delay_val.mb_tx_phy_delay = phy_map->delay.mb_tx_phy_delay;
- set_phy_delay(&delay_val);
- }
-
- if (delay_val.gb_rx_phy_delay == -1) {
- GPTP_LOG_ERROR("Warning: Gbit receive PHY delay is unknown using 0");
- delay_val.gb_rx_phy_delay = 0;
- }
- if (delay_val.gb_tx_phy_delay == -1) {
- GPTP_LOG_ERROR("Warning: Gbit transmit PHY delay is unknown using 0");
- delay_val.gb_tx_phy_delay = 0;
- }
- if (delay_val.mb_rx_phy_delay == -1) {
- GPTP_LOG_ERROR("Warning: Mbit receive PHY delay is unknown using 0");
- delay_val.mb_rx_phy_delay = 0;
- }
- if (delay_val.mb_tx_phy_delay == -1) {
- GPTP_LOG_ERROR("Warning: Mbit transmit PHY delay is unknown using 0");
- delay_val.gb_tx_phy_delay = 0;
- }
-
GPTP_LOG_INFO( "Adapter UID: %s\n", pAdapterInfo->AdapterName );
PLAT_strncpy( network_card_id, NETWORK_CARD_ID_PREFIX, 63 );
PLAT_strncpy( network_card_id+strlen(network_card_id), pAdapterInfo->AdapterName, 63-strlen(network_card_id) );
diff --git a/daemons/gptp/windows/daemon_cl/windows_hal.hpp b/daemons/gptp/windows/daemon_cl/windows_hal.hpp
index 766b7a61..f5192910 100644
--- a/daemons/gptp/windows/daemon_cl/windows_hal.hpp
+++ b/daemons/gptp/windows/daemon_cl/windows_hal.hpp
@@ -46,6 +46,7 @@
#include "avbts_osthread.hpp"
#include "packet.hpp"
#include "ieee1588.hpp"
+#include "ether_tstamper.hpp"
#include "iphlpapi.h"
#include "windows_ipc.hpp"
#include "tsc.hpp"
@@ -90,7 +91,8 @@ public:
* @param delay [in] Specifications for PHY input and output delays in nanoseconds
* @return net_result structure
*/
- virtual net_result nrecv(LinkLayerAddress *addr, uint8_t *payload, size_t &length, struct phy_delay *delay) {
+ virtual net_result nrecv( LinkLayerAddress *addr, uint8_t *payload, size_t &length )
+ {
packet_addr_t dest;
packet_error_t pferror = recvFrame( handle, &dest, payload, length );
if( pferror != PACKET_NO_ERROR && pferror != PACKET_RECVTIMEOUT_ERROR ) return net_fatal;
@@ -146,7 +148,7 @@ public:
* @param timestamper [in] HWTimestamper instance
* @return TRUE success; FALSE error
*/
- virtual bool createInterface( OSNetworkInterface **net_iface, InterfaceLabel *label, HWTimestamper *timestamper ) {
+ virtual bool createInterface( OSNetworkInterface **net_iface, InterfaceLabel *label, CommonTimestamper *timestamper ) {
WindowsPCAPNetworkInterface *net_iface_l = new WindowsPCAPNetworkInterface();
LinkLayerAddress *addr = dynamic_cast<LinkLayerAddress *>(label);
if( addr == NULL ) goto error_nofree;
@@ -603,6 +605,9 @@ typedef struct
char *device_desc;
} DeviceClockRateMapping;
+/**
+* @brief Maps network device type to device clock rate
+*/
static DeviceClockRateMapping DeviceClockRateMap[] =
{
{ 1000000000, I217_DESC },
@@ -610,24 +615,10 @@ static DeviceClockRateMapping DeviceClockRateMap[] =
{ 0, NULL },
};
-typedef struct
-{
- struct phy_delay delay;
- char *device_desc;
-} DevicePhyDelayMapping;
-
-static DevicePhyDelayMapping DevicePhyDelayMap[] =
-{
- {{ -1, -1, 6950, 8050, }, I217_DESC },
- {{ -1, -1, 6700, 7750, }, I219_DESC },
- {{ -1, -1, -1, -1 }, NULL },
-};
-
-
/**
* @brief Windows HWTimestamper implementation
*/
-class WindowsTimestamper : public HWTimestamper {
+class WindowsTimestamper : public EtherTimestamper {
private:
// No idea whether the underlying implementation is thread safe
HANDLE miniport;
@@ -723,10 +714,6 @@ public:
DWORD returned = 0;
uint64_t tx_r,tx_s;
DWORD result;
- struct phy_delay delay_val;
-
- get_phy_delay(&delay_val);//gets the phy delay
- Timestamp latency(delay_val.gb_tx_phy_delay, 0, 0);
while(( result = readOID( OID_INTEL_GET_TXSTAMP, buf_tmp, sizeof(buf_tmp), &returned )) == ERROR_SUCCESS ) {
memcpy( buf, buf_tmp, sizeof( buf ));
@@ -738,7 +725,7 @@ public:
if( returned != sizeof(buf_tmp) ) return GPTP_EC_EAGAIN;
tx_r = (((uint64_t)buf[1]) << 32) | buf[0];
tx_s = scaleNativeClockToNanoseconds( tx_r );
- timestamp = nanoseconds64ToTimestamp( tx_s ) + latency;
+ timestamp = nanoseconds64ToTimestamp( tx_s );
timestamp._version = version;
return GPTP_EC_SUCCESS;
@@ -760,10 +747,6 @@ public:
uint64_t rx_r,rx_s;
DWORD result;
uint16_t packet_sequence_id;
- struct phy_delay delay_val;
-
- get_phy_delay(&delay_val);//gets the phy delay
- Timestamp latency(delay_val.gb_rx_phy_delay, 0, 0);
while(( result = readOID( OID_INTEL_GET_RXSTAMP, buf_tmp, sizeof(buf_tmp), &returned )) == ERROR_SUCCESS ) {
memcpy( buf, buf_tmp, sizeof( buf ));
@@ -774,7 +757,7 @@ public:
if (PLAT_ntohs(packet_sequence_id) != messageId.getSequenceId()) return GPTP_EC_EAGAIN;
rx_r = (((uint64_t)buf[1]) << 32) | buf[0];
rx_s = scaleNativeClockToNanoseconds( rx_r );
- timestamp = nanoseconds64ToTimestamp( rx_s ) - latency;
+ timestamp = nanoseconds64ToTimestamp( rx_s );
timestamp._version = version;
return GPTP_EC_SUCCESS;
diff --git a/daemons/gptp/windows/gptp.sln b/daemons/gptp/windows/gptp.sln
deleted file mode 100644
index 8e0cdf65..00000000
--- a/daemons/gptp/windows/gptp.sln
+++ /dev/null
@@ -1,38 +0,0 @@
-
-Microsoft Visual Studio Solution File, Format Version 12.00
-# Visual Studio 2013
-VisualStudioVersion = 12.0.30110.0
-MinimumVisualStudioVersion = 10.0.40219.1
-Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "daemon_cl", "daemon_cl\daemon_cl.vcxproj", "{590D3055-A068-4B31-B4F9-B2ACC5F93663}"
-EndProject
-Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "named_pipe_test", "named_pipe_test\named_pipe_test.vcxproj", "{303FACBB-2A44-4511-A855-2B5B2C0E3A89}"
-EndProject
-Global
- GlobalSection(SolutionConfigurationPlatforms) = preSolution
- Debug|Win32 = Debug|Win32
- Debug|x64 = Debug|x64
- Release|Win32 = Release|Win32
- Release|x64 = Release|x64
- EndGlobalSection
- GlobalSection(ProjectConfigurationPlatforms) = postSolution
- {590D3055-A068-4B31-B4F9-B2ACC5F93663}.Debug|Win32.ActiveCfg = Debug|Win32
- {590D3055-A068-4B31-B4F9-B2ACC5F93663}.Debug|Win32.Build.0 = Debug|Win32
- {590D3055-A068-4B31-B4F9-B2ACC5F93663}.Debug|x64.ActiveCfg = Debug|x64
- {590D3055-A068-4B31-B4F9-B2ACC5F93663}.Debug|x64.Build.0 = Debug|x64
- {590D3055-A068-4B31-B4F9-B2ACC5F93663}.Release|Win32.ActiveCfg = Release|Win32
- {590D3055-A068-4B31-B4F9-B2ACC5F93663}.Release|Win32.Build.0 = Release|Win32
- {590D3055-A068-4B31-B4F9-B2ACC5F93663}.Release|x64.ActiveCfg = Release|x64
- {590D3055-A068-4B31-B4F9-B2ACC5F93663}.Release|x64.Build.0 = Release|x64
- {303FACBB-2A44-4511-A855-2B5B2C0E3A89}.Debug|Win32.ActiveCfg = Debug|Win32
- {303FACBB-2A44-4511-A855-2B5B2C0E3A89}.Debug|Win32.Build.0 = Debug|Win32
- {303FACBB-2A44-4511-A855-2B5B2C0E3A89}.Debug|x64.ActiveCfg = Debug|x64
- {303FACBB-2A44-4511-A855-2B5B2C0E3A89}.Debug|x64.Build.0 = Debug|x64
- {303FACBB-2A44-4511-A855-2B5B2C0E3A89}.Release|Win32.ActiveCfg = Release|Win32
- {303FACBB-2A44-4511-A855-2B5B2C0E3A89}.Release|Win32.Build.0 = Release|Win32
- {303FACBB-2A44-4511-A855-2B5B2C0E3A89}.Release|x64.ActiveCfg = Release|x64
- {303FACBB-2A44-4511-A855-2B5B2C0E3A89}.Release|x64.Build.0 = Release|x64
- EndGlobalSection
- GlobalSection(SolutionProperties) = preSolution
- HideSolutionNode = FALSE
- EndGlobalSection
-EndGlobal