Speed and Distance API

This is a collection of classes for processing and sending ISOBUS speed messages.

class SpeedMessagesInterface

This interface manages and parses ISOBUS speed messages.

Public Types

enum class MachineDirection : std::uint8_t

Enumerates the values of the direction of travel for the machine.

Values:

enumerator Forward
enumerator Reverse
enumerator Error
enumerator NotAvailable

Public Functions

SpeedMessagesInterface(std::shared_ptr<InternalControlFunction> source, bool enableSendingGroundBasedSpeedPeriodically = false, bool enableSendingWheelBasedSpeedPeriodically = false, bool enableSendingMachineSelectedSpeedPeriodically = false, bool enableSendingMachineSelectedSpeedCommandPeriodically = false)

Constructor for a SpeedMessagesInterface.

Note

Normally you would only configure this interface to transmit if you are serving as the tractor ECU (TECU).

Parameters:
  • source[in] The internal control function to use when sending messages, or nullptr for listen only

  • enableSendingGroundBasedSpeedPeriodically[in] If true, ground-based speed will be sent periodically. (Normally you will not want to send this unless you are sensing the speed yourself)

  • enableSendingWheelBasedSpeedPeriodically[in] If true, wheel-based speed will be sent periodically. (Normally you will not want to send this unless you are sensing the speed yourself)

  • enableSendingMachineSelectedSpeedPeriodically[in] If true, machine-selected speed will be sent periodically. (Normally you will not want to send this unless you are selecting the speed yourself)

  • enableSendingMachineSelectedSpeedCommandPeriodically[in] If true, machine-selected speed command will be sent periodically. (Normally you will not want to send this unless you are intending to cause machine motion)

~SpeedMessagesInterface()

Destructor for SpeedMessagesInterface. Cleans up PGN registrations if needed.

void initialize()

Sets up the class and registers it to receive callbacks from the network manager for processing guidance messages. The class will not receive messages if this is not called.

bool get_initialized() const

Returns if the interface has been initialized.

Returns:

true if initialize has been called for this interface, otherwise false

std::size_t get_number_received_wheel_based_speed_sources() const

Returns the number of received, unique wheel-based speed message sources.

Returns:

The number of CFs sending the wheel-based speed message

std::size_t get_number_received_ground_based_speed_sources() const

Returns the number of received, unique ground-based speed message sources.

Returns:

The number of CFs sending the ground-based speed message

std::size_t get_number_received_machine_selected_speed_sources() const

Returns the number of received, unique machine selected speed message sources.

Returns:

The number of CFs sending the machine selected speed message

std::size_t get_number_received_machine_selected_speed_command_sources() const

Returns the number of received, unique machine selected speed command message sources.

Returns:

The number of CFs sending the machine selected speed command message

std::shared_ptr<MachineSelectedSpeedData> get_received_machine_selected_speed(std::size_t index)

Returns the content of the machine selected speed message based on the index of the sender. Use this to read the received messages’ content.

Note

Only one device on the bus will send this normally, but we provide a generic way to get an arbitrary number of these commands. So generally using only index 0 will be acceptable.

Note

It is also possible that this message may not be present, depending on your machine.

Parameters:

index[in] An index of senders of the machine selected speed message

Returns:

The parsed content of the machine selected speed message

std::shared_ptr<WheelBasedMachineSpeedData> get_received_wheel_based_speed(std::size_t index)

Returns the content of the wheel-based speed message based on the index of the sender. Use this to read the received messages’ content.

Note

Only one device on the bus will send this normally, but we provide a generic way to get an arbitrary number of these commands. So generally using only index 0 will be acceptable.

Note

It is also possible that this message may not be present, depending on your machine.

Parameters:

index[in] An index of senders of the wheel-based speed message

Returns:

The parsed content of the wheel-based speed message

std::shared_ptr<GroundBasedSpeedData> get_received_ground_based_speed(std::size_t index)

Returns the content of the ground-based speed message based on the index of the sender. Use this to read the received messages’ content.

Note

Only one device on the bus will send this normally, but we provide a generic way to get an arbitrary number of these commands. So generally using only index 0 will be acceptable.

Note

It is also possible that this message may not be present, depending on your machine.

Parameters:

index[in] An index of senders of the ground-based speed message

Returns:

The parsed content of the ground-based speed message

std::shared_ptr<MachineSelectedSpeedCommandData> get_received_machine_selected_speed_command(std::size_t index)

Returns the content of the machine selected speed command message based on the index of the sender. Use this to read the received messages’ content.

Note

Only one device on the bus will send this normally, but we provide a generic way to get an arbitrary number of these commands. So generally using only index 0 will be acceptable.

Note

It is also possible that this message may not be present, depending on your machine.

Parameters:

index[in] An index of senders of the machine selected speed command message

Returns:

The parsed content of the machine selected speed command message

EventDispatcher<const std::shared_ptr<WheelBasedMachineSpeedData>, bool> &get_wheel_based_machine_speed_data_event_publisher()

Returns an event dispatcher which you can use to get callbacks when new/updated wheel-based speed messages are received.

Returns:

The event publisher for wheel-based speed messages

EventDispatcher<const std::shared_ptr<MachineSelectedSpeedData>, bool> &get_machine_selected_speed_data_event_publisher()

Returns an event dispatcher which you can use to get callbacks when new/updated machine selected speed messages are received.

Returns:

The event publisher for machine selected speed messages

EventDispatcher<const std::shared_ptr<GroundBasedSpeedData>, bool> &get_ground_based_machine_speed_data_event_publisher()

Returns an event dispatcher which you can use to get callbacks when new/updated ground-based speed messages are received.

Returns:

The event publisher for ground-based speed messages

EventDispatcher<const std::shared_ptr<MachineSelectedSpeedCommandData>, bool> &get_machine_selected_speed_command_data_event_publisher()

Returns an event dispatcher which you can use to get callbacks when new/updated machine selected speed command messages are received.

Returns:

The event publisher for machine selected speed command messages

void update()

Call this cyclically to update the interface. Transmits messages if needed and processes timeouts for received messages.

Public Members

MachineSelectedSpeedData machineSelectedSpeedTransmitData

Use this to configure transmission of the machine selected speed message. If you pass in an internal control function to the constructor of this class, then this message is available to be sent.

WheelBasedMachineSpeedData wheelBasedSpeedTransmitData

Use this to configure transmission of the wheel-based speed message. If you pass in an internal control function to the constructor of this class, then this message is available to be sent.

GroundBasedSpeedData groundBasedSpeedTransmitData

Use this to configure transmission of the ground-based speed message. If you pass in an internal control function to the constructor of this class, then this message is available to be sent.

MachineSelectedSpeedCommandData machineSelectedSpeedCommandTransmitData

Use this to configure transmission of the machine selected speed command message. If you pass in an internal control function to the constructor of this class, then this message is available to be sent.

class GroundBasedSpeedData

Message normally sent by the Tractor ECU on the implement bus on construction and agricultural implements providing to connected systems the current measured ground speed (also includes a free-running distance counter and an indication of the direction of travel).

Note

Accuracies of both wheel-based and ground-based sources can be speed-dependent and degrade at low speeds. Wheel-based information might not be updated at the 100ms rate at low speeds.

Public Functions

explicit GroundBasedSpeedData(std::shared_ptr<ControlFunction> sender)

Constructor for a GroundBasedSpeedData.

Parameters:

sender[in] The control function that is sending this message

std::uint32_t get_machine_distance() const

Actual distance traveled by a machine, based on measurements from a sensor such as that is not susceptible to wheel slip (e.g. radar, GPS, LIDAR, or stationary object tracking)

Note

This distance is usually provided by radar.

Returns:

Actual distance traveled by a machine, based on measurements from a sensor such as that is not susceptible to wheel slip (millimeters)

bool set_machine_distance(std::uint32_t distance)

Sets the actual distance traveled by a machine, based on measurements from a sensor such as that is not susceptible to wheel slip.

Note

This distance is usually provided by radar.

Parameters:

distance – The actual distance traveled by a machine (millimeters)

Returns:

True if the set value was different from the stored value otherwise false

std::uint16_t get_machine_speed() const

Returns the actual ground speed of a machine, measured by a sensor such as that is not susceptible to wheel slip in mm/s.

Note

This speed is usually provided by radar.

Returns:

The actual ground speed of a machine, measured by a sensor such as that is not susceptible to wheel slip in mm/s

bool set_machine_speed(std::uint16_t speed)

Sets the actual ground speed of a machine, measured by a sensor such as that is not susceptible to wheel slip in mm/s.

Note

This speed is usually provided by radar.

Parameters:

speed – The actual ground speed of a machine, measured by a sensor such as that is not susceptible to wheel slip in mm/s

Returns:

True if the set value was different from the stored value otherwise false

MachineDirection get_machine_direction_of_travel() const

Returns A measured signal indicating either forward or reverse as the direction of travel.

Note

When the speed is zero, this indicates the last travel direction until a different direction is detected or selected and engaged.

Returns:

The measured direction of travel for the machine

bool set_machine_direction_of_travel(MachineDirection directionOfTravel)

Sets a measured signal indicating either forward or reverse as the direction of travel.

Note

The “Not Off” key switch state does not always mean “On” so use care when using it.

Parameters:

directionOfTravel – The measured direction of travel for the machine

Returns:

True if the set value was different from the stored value otherwise false

std::shared_ptr<ControlFunction> get_sender_control_function() const

Returns a pointer to the sender of the message. If an ICF is the sender, returns the ICF being used to transmit from.

Attention

The only way you could get an invalid pointer here is if you register a partner, it sends this message, then you delete the partner and call this function, as that is the only time the stack deletes a control function. That would be abnormal program flow, but at some point the stack will be updated to return a shared or weak pointer instead, but for now please be aware of that limitation. Eventually though the message will time-out normally and you can get a new pointer for the external CF that replaces the deleted partner.

Returns:

The control function sending this instance of the guidance system command message

void set_timestamp_ms(std::uint32_t timestamp)

Sets the timestamp for when the message was received or sent.

Parameters:

timestamp[in] The timestamp, in milliseconds, when the message was sent or received

std::uint32_t get_timestamp_ms() const

Returns the timestamp for when the message was received, in milliseconds.

Returns:

The timestamp for when the message was received, in milliseconds

class MachineSelectedSpeedCommandData

Message that provides the control of the machine speed and direction. If you receive this message, you can sniff the speed commands being sent to the TECU or act as the TECU or propulsion interface yourself.

Attention

Use extreme caution if you choose to send this message, as you may cause machine motion!

Public Functions

explicit MachineSelectedSpeedCommandData(std::shared_ptr<ControlFunction> sender)

Constructor for a MachineSelectedSpeedCommandData.

Parameters:

sender[in] The control function that is sending this message

std::uint16_t get_machine_speed_setpoint_command() const

Returns the commanded setpoint value of the machine speed as measured by the selected source in mm/s.

Returns:

The commanded setpoint value of the machine speed as measured by the selected source in mm/s

bool set_machine_speed_setpoint_command(std::uint16_t speed)

Sets The commanded setpoint value of the machine speed as measured by the selected source in mm/s.

Attention

This is used to set the speed of the machine! Use with caution!

Parameters:

speed – The commanded setpoint value of the machine speed as measured by the selected source in mm/s

Returns:

True if the set value was different from the stored value otherwise false

std::uint16_t get_machine_selected_speed_setpoint_limit() const

Returns the machine’s maximum allowed speed in mm/s, which get’s communicated to the tractor/machine.

Returns:

The machine’s maximum allowed speed in mm/s, which get’s communicated to the tractor/machine

bool set_machine_selected_speed_setpoint_limit(std::uint16_t speedLimit)

Sets the maximum allowed machine speed in mm/s, which gets communicated to the tractor/machine.

Parameters:

speedLimit[in] The maximum allowed machine speed in mm/s

Returns:

True if the set value was different from the stored value otherwise false

MachineDirection get_machine_direction_command() const

Returns The commanded direction of the machine.

Returns:

The commanded direction of the machine.

bool set_machine_direction_of_travel(MachineDirection commandedDirection)

Sets the commanded direction of the machine.

Parameters:

commandedDirection – The commanded direction of travel for the machine

Returns:

True if the set value was different from the stored value otherwise false

std::shared_ptr<ControlFunction> get_sender_control_function() const

Returns a pointer to the sender of the message. If an ICF is the sender, returns the ICF being used to transmit from.

Attention

The only way you could get an invalid pointer here is if you register a partner, it sends this message, then you delete the partner and call this function, as that is the only time the stack deletes a control function. That would be abnormal program flow, but at some point the stack will be updated to return a shared or weak pointer instead, but for now please be aware of that limitation. Eventually though the message will time-out normally and you can get a new pointer for the external CF that replaces the deleted partner.

Returns:

The control function sending this instance of the guidance system command message

void set_timestamp_ms(std::uint32_t timestamp)

Sets the timestamp for when the message was received or sent.

Parameters:

timestamp[in] The timestamp, in milliseconds, when the message was sent or received

std::uint32_t get_timestamp_ms() const

Returns the timestamp for when the message was received, in milliseconds.

Returns:

The timestamp for when the message was received, in milliseconds

class MachineSelectedSpeedData

Message that provides the current machine selected speed, direction and source parameters.

This is usually the best/authoritative source of speed information as chosen by the machine.

Public Types

enum class ExitReasonCode : std::uint8_t

This parameter is used to indicate why the vehicle speed control unit cannot currently accept remote commands or has most recently stopped accepting remote commands.

Note

Some values are reserved or manufacturer specific. See the SPN definition.

Values:

enumerator NoReasonAllClear
enumerator RequiredLevelOfOperatorPresenceAwarenessNotDetected
enumerator ImplementReleasedControlOfFunction
enumerator OperatorOverrideOfFunction
enumerator OperatorControlNotInValidPosition
enumerator RemoteCommandTimeout
enumerator RemoteCommandOutOfRangeInvalid
enumerator FunctionNotCalibrated
enumerator OperatorControlFault
enumerator FunctionFault
enumerator VehicleTransmissionGearDoesNotAllowRemoteCommands
enumerator Error
enumerator NotAvailable
enum class SpeedSource : std::uint8_t

An indication of the speed source that is currently being reported in the machine selected speed parameter.

This parameter is an indication of the speed source that is currently being reported in the machine selected speed parameter. Simulated speed is a system-generated speed message to permit implement operations when the machine is not actually moving. Blended speed is a speed message that uses a combination of the actual speed sources based on the operator’s or the manufacturer’s selected logic, i.e. when a ground-based speed source is less than 0.5 m/s, the speed message will then send the wheel speed source.

Values:

enumerator WheelBasedSpeed

Wheel encoder usually.

enumerator GroundBasedSpeed

Radar usually.

enumerator NavigationBasedSpeed

GNSS Usually.

enumerator Blended

Some combination of source fusion.

enumerator Simulated

A test speed.

enumerator Reserved_1

Reserved.

enumerator Reserved_2

Reserved.

enumerator NotAvailable

N/A.

enum class LimitStatus : std::uint8_t

This parameter is used to report the Tractor ECU’s present limit status associated with a parameter whose commands are persistent. Similar to other SAEbs03 limit statuses.

Values:

enumerator NotLimited
enumerator OperatorLimitedControlled

Request cannot be implemented.

enumerator LimitedHigh

Only lower command values result in a change.

enumerator LimitedLow

Only higher command values result in a change.

enumerator Reserved_1

Reserved.

enumerator Reserved_2

Reserved.

enumerator NonRecoverableFault
enumerator NotAvailable

Parameter not supported.

Public Functions

explicit MachineSelectedSpeedData(std::shared_ptr<ControlFunction> sender)

Constructor for a MachineSelectedSpeedData.

Parameters:

sender[in] The control function that is sending this message

std::uint32_t get_machine_distance() const

Returns the Actual distance travelled by the machine based on the value of selected machine speed (SPN 4305).

Note

When the distance exceeds 4211081215 meters the value shall be reset to zero and incremented as additional distance accrues.

Returns:

The Actual distance travelled by the machine based on the value of selected machine speed (millimeters)

bool set_machine_distance(std::uint32_t distance)

Sets the Actual distance travelled by the machine based on the value of selected machine speed (SPN 4305).

Note

When the distance exceeds 4211081215 meters the value shall be reset to zero and incremented as additional distance accrues.

Parameters:

distance[in] The Actual distance travelled by the machine based on the value of selected machine speed (millimeters)

Returns:

True if the set value was different from the stored value otherwise false

std::uint16_t get_machine_speed() const

Returns the current machine selected speed.

The TECU sends this value as the authoritative speed for the machine.

Returns:

The current machine selected speed in mm/s

bool set_machine_speed(std::uint16_t speed)

Sets the machine selected speed.

Parameters:

speed – The machine selected speed in mm/s

Returns:

True if the set value was different from the stored value otherwise false

std::uint8_t get_exit_reason_code() const

Returns the reason why the vehicle speed control unit cannot currently accept remote commands or has most recently stopped accepting remote commands.

Returns:

why the vehicle speed control unit cannot currently accept remote commands or has most recently stopped accepting remote commands

bool set_exit_reason_code(std::uint8_t exitCode)

Sets the reason why the vehicle speed control unit cannot currently accept remote commands or has most recently stopped accepting remote commands.

Parameters:

exitCode – The exit/reason code to set

Returns:

True if the set value was different from the stored value otherwise false

SpeedSource get_speed_source() const

Returns the speed source that is currently being reported in the machine selected speed parameter (SPN-4305).

Returns:

The speed source that is currently being reported in the machine selected speed parameter (SPN-4305).

bool set_speed_source(SpeedSource selectedSource)

Sets the speed source that is currently being reported in the machine selected speed parameter (SPN-4305).

Parameters:

selectedSource – The speed source that is currently being reported in the machine selected speed parameter (SPN-4305).

Returns:

True if the set value was different from the stored value otherwise false

LimitStatus get_limit_status() const

Returns The Tractor ECU’s present limit status associated with a parameter whose commands are persistent.

Returns:

The Tractor ECU’s present limit status associated with a parameter whose commands are persistent

bool set_limit_status(LimitStatus statusToSet)

Sets the Tractor ECU’s present limit status associated with a parameter whose commands are persistent.

Parameters:

statusToSet – The Tractor ECU’s present limit status associated with a parameter whose commands are persistent

Returns:

True if the set value was different from the stored value otherwise false

MachineDirection get_machine_direction_of_travel() const

Returns A measured signal indicating either forward or reverse as the direction of travel.

Note

When the speed is zero, this indicates the last travel direction until a different direction is detected or selected and engaged.

Returns:

The measured direction of travel for the machine

bool set_machine_direction_of_travel(MachineDirection directionOfTravel)

Sets a measured signal indicating either forward or reverse as the direction of travel.

Note

The “Not Off” key switch state does not always mean “On” so use care when using it.

Parameters:

directionOfTravel – The measured direction of travel for the machine

Returns:

True if the set value was different from the stored value otherwise false

std::shared_ptr<ControlFunction> get_sender_control_function() const

Returns a pointer to the sender of the message. If an ICF is the sender, returns the ICF being used to transmit from.

Attention

The only way you could get an invalid pointer here is if you register a partner, it sends this message, then you delete the partner and call this function, as that is the only time the stack deletes a control function. That would be abnormal program flow, but at some point the stack will be updated to return a shared or weak pointer instead, but for now please be aware of that limitation. Eventually though the message will time-out normally and you can get a new pointer for the external CF that replaces the deleted partner.

Returns:

The control function sending this instance of the guidance system command message

void set_timestamp_ms(std::uint32_t timestamp)

Sets the timestamp for when the message was received or sent.

Parameters:

timestamp[in] The timestamp, in milliseconds, when the message was sent or received

std::uint32_t get_timestamp_ms() const

Returns the timestamp for when the message was received, in milliseconds.

Returns:

The timestamp for when the message was received, in milliseconds

class WheelBasedMachineSpeedData

Groups the data encoded in an ISO “Wheel-based Speed and Distance” message.

Public Types

enum class KeySwitchState : std::uint8_t

Enumerates the key switch states of the tractor or power unit.

Values:

enumerator Off

Key is off.

enumerator NotOff

Key is not off (does not always mean that it’s on!)

enumerator Error
enumerator NotAvailable
enum class ImplementStartStopOperations : std::uint8_t

Enumerates the states of a switch or operator input to start or enable implement operations.

Values:

enumerator StopDisableImplementOperations
enumerator StartEnableImplementOperations
enumerator Error
enumerator NotAvailable
enum class OperatorDirectionReversed : std::uint8_t

This parameter indicates whether the reported direction is reversed from the perspective of the operator.

Values:

enumerator NotReversed
enumerator Reversed
enumerator Error
enumerator NotAvailable

Public Functions

explicit WheelBasedMachineSpeedData(std::shared_ptr<ControlFunction> sender)

Constructor for a WheelBasedMachineSpeedData.

Parameters:

sender[in] The control function that is sending this message

std::uint32_t get_machine_distance() const

Returns The distance traveled by a machine as calculated from wheel or tail-shaft speed.

Note

When the distance exceeds 4211081215m the value shall be reset to zero and incremented as additional distance accrues.

Returns:

The distance traveled by a machine as calculated from wheel or tail-shaft speed. (millimeters)

bool set_machine_distance(std::uint32_t distance)

Sets the distance traveled by a machine as calculated from wheel or tail-shaft speed.

Parameters:

distance – The distance traveled by a machine as calculated from wheel or tail-shaft speed. (millimeters)

Returns:

True if the set value was different from the stored value otherwise false

std::uint16_t get_machine_speed() const

Returns the value of the speed of a machine as calculated from the measured wheel or tail-shaft speed.

Returns:

The value of the speed of a machine as calculated from the measured wheel or tail-shaft speed.

bool set_machine_speed(std::uint16_t speed)

Sets the value of the speed of a machine as calculated from the measured wheel or tail-shaft speed.

Parameters:

speed – The value of the speed of a machine as calculated from the measured wheel or tail-shaft speed.

Returns:

True if the set value was different from the stored value otherwise false

std::uint8_t get_maximum_time_of_tractor_power() const

Returns the maximum time (in minutes) of remaining tractor or power-unit-supplied electrical power at the current load.

Returns:

The maximum time of remaining tractor or power-unit-supplied electrical power at the current load (in minutes)

bool set_maximum_time_of_tractor_power(std::uint8_t maxTime)

Sets the maximum time (in minutes) of remaining tractor or power-unit-supplied electrical power at the current load.

Parameters:

maxTime – The maximum time of remaining tractor or power-unit-supplied electrical power at the current load (in minutes)

Returns:

True if the set value was different from the stored value otherwise false

MachineDirection get_machine_direction_of_travel() const

Returns A measured signal indicating either forward or reverse as the direction of travel.

Note

When the speed is zero, this indicates the last travel direction until a different direction is detected or selected and engaged.

Returns:

The measured direction of travel for the machine

bool set_machine_direction_of_travel(MachineDirection direction)

Sets a measured signal indicating either forward or reverse as the direction of travel.

Note

The “Not Off” key switch state does not always mean “On” so use care when using it.

Parameters:

direction – The measured direction of travel for the machine

Returns:

True if the set value was different from the stored value otherwise false

KeySwitchState get_key_switch_state() const

Returns the key switch state of the tractor or power unit.

Returns:

The key switch state of the tractor or power unit.

bool set_key_switch_state(KeySwitchState state)

Sets the reported key switch state of the tractor or power unit.

Note

The “Not Off” key switch state does not always mean “On” so use care when using it.

Parameters:

state – The key switch state of the tractor or power unit.

Returns:

True if the set value was different from the stored value otherwise false

ImplementStartStopOperations get_implement_start_stop_operations_state() const

Returns the state of a switch or other operator input to start or enable implement operations.

The start or enabled state can be the result of the implement being positioned in an operating position. It can be generated by an operator placing a switch to an ON state. Also called “Master ON/OFF” switch.

Returns:

The state of a switch or other operator input to start or enable implement operations.

bool set_implement_start_stop_operations_state(ImplementStartStopOperations state)

Sets the state of a switch or other operator input to start or enable implement operations.

The start or enabled state can be the result of the implement being positioned in an operating position. It can be generated by an operator placing a switch to an ON state. Also called “Master ON/OFF” switch.

Parameters:

state – The state of a switch or other operator input to start or enable implement operations.

Returns:

True if the set value was different from the stored value otherwise false

OperatorDirectionReversed get_operator_direction_reversed_state() const

Returns whether the reported direction is reversed from the perspective of the operator.

Returns:

Whether the reported direction is reversed from the perspective of the operator or not

bool set_operator_direction_reversed_state(OperatorDirectionReversed reverseState)

Sets whether the reported direction is reversed from the perspective of the operator.

Parameters:

reverseState – The state of whether the reported direction is reversed from the perspective of the operator

Returns:

True if the set value was different from the stored value otherwise false

std::shared_ptr<ControlFunction> get_sender_control_function() const

Returns a pointer to the sender of the message. If an ICF is the sender, returns the ICF being used to transmit from.

Attention

The only way you could get an invalid pointer here is if you register a partner, it sends this message, then you delete the partner and call this function, as that is the only time the stack deletes a control function. That would be abnormal program flow, but at some point the stack will be updated to return a shared or weak pointer instead, but for now please be aware of that limitation. Eventually though the message will time-out normally and you can get a new pointer for the external CF that replaces the deleted partner.

Returns:

The control function sending this instance of the guidance system command message

void set_timestamp_ms(std::uint32_t timestamp)

Sets the timestamp for when the message was received or sent.

Parameters:

timestamp[in] The timestamp, in milliseconds, when the message was sent or received

std::uint32_t get_timestamp_ms() const

Returns the timestamp for when the message was received, in milliseconds.

Returns:

The timestamp for when the message was received, in milliseconds