![]() |
ImFusion SDK 4.3
|
#include <RoboticsPlugin/Include/ImFusion/Robotics/RobotStateStream.h>
Stream data containing robot state information. More...
Inheritance diagram for RobotStateStreamData:Stream data containing robot state information.
This class is the payload emitted by the signalNewData Signal of RobotStateStream child classes. Each instance of RobotStateStreamData holds a RobotState instance that captures the robot's status at the moment the signal is emitted. This includes at least the joint positions, enabling to compute the forward kinematics of and determine the Cartesian configuration of the robot. The RobotState can also include the joint velocities and further information provided by the robot firmware.
Each robot integration may subclass RobotState to further extend the information provided to the user.
It is recommended to use the RobotState instance passed to a listener of RobotStateStream::signalNewData to get the spatial information of the robot. Mixing the information contained in the RobotState instance and queried directly by the stream may lead to incoherences, if the robot registration / TCP transform has changed since the time of emission of the payload.
Public Member Functions | |
| RobotStateStreamData (Stream *stream, std::shared_ptr< const RobotState > state) | |
| Create new data container for robot stream information. | |
| const RobotState * | robotState () const |
| Read-only access to the current robot state. | |
| std::unique_ptr< StreamData > | clone () const override |
Public Member Functions inherited from StreamData | |
| virtual Stream * | stream () const |
| Returns the stream object which updates this data. | |
| virtual unsigned long long | timestampDevice () const |
| Timestamp in milliseconds. Set by the streaming device. | |
| virtual void | setTimestampDevice (unsigned long long time) |
| Set timestamp provided by the streaming device, in milliseconds. | |
| virtual unsigned long long | timestampArrival () const |
| Timestamp in milliseconds. Based on message's arrival time. | |
| virtual void | setTimestampArrival (std::chrono::system_clock::time_point time) |
| Set the system time when this streamData was arrived. It will be stored in milliseconds relative to epoch time. | |
| virtual void | setTimestampArrival (unsigned long long time) |
| Set arrival timestamp manually, in milliseconds. | |
| const DataComponentList & | components () const |
| Returns the list of DataComponents for this data. | |
| DataComponentList & | components () |
| Returns the list of DataComponents for this data. | |
| template<typename StreamDataClass> | |
| const StreamDataClass * | typed () const |
Additional Inherited Members | |
Protected Member Functions inherited from StreamData | |
| StreamData (const StreamData &other)=default | |
| StreamData (Stream *stream) | |
| StreamData (Stream *stream, DataComponentList &&components) | |
Protected Attributes inherited from StreamData | |
| Stream * | m_stream |
| The stream object which updates this data. | |
| unsigned long long | m_timestampDevice |
| Timestamp of the streaming device, in milliseconds. | |
| unsigned long long | m_timestampArrival |
| Timestamp when the data is received in ImFusion framework, in milliseconds. | |
| DataComponentList | m_dataComponentList |
| The list of DataComponents for this StreamData. | |
|
inline |
Create new data container for robot stream information.
| stream | non-owning pointer to the parent stream |
| state | current robot state to be encapsulated |
|
inline |
Read-only access to the current robot state.
|
inlineoverridevirtual |
Implements StreamData.