ImFusion SDK 4.3
RobotState Class Reference

#include <RoboticsPlugin/Include/ImFusion/Robotics/RobotState.h>

Contains the current status of the robot (i.e. More...

+ Inheritance diagram for RobotState:

Detailed Description

Contains the current status of the robot (i.e.

joint positions) and a reference to the model It can lazily perform forward kinematics to provide the Cartesian state of the robot (position of each link), in particular if the pose of the end effector (or the flange) is not provided by the robot firmware. Each arm state stream can inherit from this class to include additional reported information (e.g integrated sensors or IO ports)

Public Member Functions

 RobotState (const std::shared_ptr< const RobotInstance > &instance)
 Initialize robot state where all joint values are set to zero.
 
 RobotState (std::shared_ptr< const RobotInstance > instance, const JointState &jointState)
 
 RobotState (std::shared_ptr< const RobotInstance > instance, const JointState &jointState, const std::optional< CartesianFrames > &cartesianFrames, unsigned long long timeStamp, unsigned long long timestampArrival)
 Initialize robot state with the given joint states and log errors.
 
virtual std::optional< RobotArmCartesianStatecartesianState () const
 attempts computing the FK and returns a reference if successful
 
const JointStatejointState () const
 
const CartesianFramescartesianFrames () const
 
std::optional< isom3 > base_T_flange () const
 
std::optional< isom3 > base_T_effector () const
 Retrieve the transformation end-effector-to-base.
 
std::optional< isom3 > world_T_refFrame (ReferenceFrame frame) const
 
std::optional< isom3 > world_T_effector () const
 
std::optional< isom3 > world_T_flange () const
 
std::optional< isom3 > world_T_namedLink (const std::string &linkName) const
 Retrieve the transformation from a particularly named link to the world.
 
std::shared_ptr< const RobotInstancerobotInstance () const
 
const RobotInstancerobotInstanceRef () const
 

Public Attributes

unsigned long long m_timeStamp = 0
 Timestamp in milliseconds.
 
unsigned long long m_timestampArrival = 0
 Timestamp of data reception in the ImFusion framework (milliseconds).
 
std::shared_ptr< const NativeRobotStateBasem_nativeRobotState
 

Protected Attributes

std::shared_ptr< const RobotInstancem_robotInstance
 Geometric representation of the robot's structure.
 
JointState m_jointState
 Joint positions as reported by the robot firmware.
 
std::optional< CartesianFramesm_cartesianFrames
 Cartesian poses of notable frames as reported by the robot firmware (if supported)
 
std::optional< RobotArmCartesianStatem_cartesianState
 State computed lazily using forward kinematics.
 

Constructor & Destructor Documentation

◆ RobotState() [1/2]

RobotState ( const std::shared_ptr< const RobotInstance > & instance)
explicit

Initialize robot state where all joint values are set to zero.

Parameters
instanceencapsulates the robot model and manages its kinematic variables (i.e robot's world position, TCP transforms) and provides methods for forward and inverse kinematics in world (or robot base) coordinates, with access to the underlying robot model.

◆ RobotState() [2/2]

RobotState ( std::shared_ptr< const RobotInstance > instance,
const JointState & jointState,
const std::optional< CartesianFrames > & cartesianFrames,
unsigned long long timeStamp,
unsigned long long timestampArrival )

Initialize robot state with the given joint states and log errors.

Parameters
instanceencapsulates the robot model and manages its kinematic variables (i.e robot's world position, TCP transforms) and provides methods for forward and inverse kinematics in world (or robot base) coordinates, with access to the underlying robot model. If not defined (null) an error is logged.
jointStatethe joint states of the robot. The vector size must match the instance model's expected size. In case of mismatch an error is logged.
cartesianFramesnotable frames as reported by the robot firmware.
timeStamptimestamp in milliseconds (for compatibility with the rest of the SDK), as reported by the robot firmware.
timestampArrivaltimestamp in milliseconds (for compatibility with the rest of the SDK), reporting the first time the information reached the SDK boundary.

Member Function Documentation

◆ base_T_effector()

std::optional< isom3 > base_T_effector ( ) const

Retrieve the transformation end-effector-to-base.

Returns
The measured pose if this class instance contains valid notable Cartesian frame denoted as end-effector-to-base transformation. Otherwise:
  • The product of the flange-to-base pose and the valid notable Cartesian frame with a end-effector-to-flange.
  • If unavailable, the product of the Cartesian frame (derived via lazy forward kinematics) in this class instance and the end-effector-to-flange transformation if defined in the robot instance. If an "overridden" end-effector-to-flange transformation is defined, the transformation is updated by first applying the inverse of the original end-effector-to-flange transformation, then multiplying it by the overridden transformation.

◆ world_T_namedLink()

std::optional< isom3 > world_T_namedLink ( const std::string & linkName) const

Retrieve the transformation from a particularly named link to the world.

Returns
the homogeneous transformation matrix if the link is found, or an empty optional if the link does not exist.

Member Data Documentation

◆ m_timestampArrival

unsigned long long m_timestampArrival = 0

Timestamp of data reception in the ImFusion framework (milliseconds).

Set by RobotRunner, not by the stream (unlike the arrival timestamp in StreamData).


The documentation for this class was generated from the following file:
Search Tab / S to search, Esc to close