ImFusion SDK 4.3
RobotInstance Class Reference

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

A class that manages a robot's kinematic model and coordinate transformations in the ImFusion SDK. More...

+ Inheritance diagram for RobotInstance:

Detailed Description

A class that manages a robot's kinematic model and coordinate transformations in the ImFusion SDK.

The RobotInstance class encapsulates RobotModel and manages the coordinate transformations necessary for robot control and motion planning. It serves as central representation of a robot's configuration and maintains several key transformations

  • world_T_base: The robot's base pose in world coordinates (analogous to the RegistrationMatrix for image(s) or tracking data)
  • flange_T_effector_override: Optional override for the tool center point (TCP) If no override is specified, the TCP transform defaults to the one defined in the RobotModel.

It provides both high-level and low-level kinematics access: High-level world coordinate operations

isom3 world_T_effector = instance.forwardKinematics(jointPositions);
std::vector<double> joints = instance.inverseKinematics(world_T_effector);

Low-level base-coordinate operations (via Robot ModeL)

auto model = instance.robotModel();
isom3 base_T_flange = model->forwardKinematics(jointPositions);

The RobotInstance class is typically shared between multiple components for:

  • motion validation (
    See also
    RobotRunner)
  • robot display (
    See also
    GoalStateVisualization)
  • trajectory generation (
    See also
    MotionGenerationBase)
  • limit checking
Note
All Cartesian operations in the RobotInstance class use world coordinates and consider the overridden TCP transform while the underlying RobotModel operates in base coordinates with the original TCP transform.

Classes

struct  AttachedObject
 Defines the relationship between an attached object and the robot's end effector (EE), along with a file path to the object's mesh. More...
 

Public Member Functions

 RobotInstance (std::shared_ptr< const RobotModel > model)
 Create Robot Instance with the corresponding Robot Model.
 
void configure (const Properties *p) override
 Initialize the robot instance's spatial setup and attached tools/objects.
 
void configuration (Properties *p) const override
 Retrieve the current robot instance properties into a Properties object for later persistence or serialization.
 
std::shared_ptr< const RobotModelrobotModel () const
 Access to the robot's kinematic and dynamic model.
 
const RobotModelrobotModelRef () const
 Read-only access to the robot's kinematic and dynamic model.
 
std::shared_ptr< const RobotGroupactiveGroup () const
 
bool setActiveGroup (const std::string &name, const RobotState *prevState=nullptr)
 
bool validJointPosition (const JointPosition &jointPosition) const
 
std::optional< RobotArmCartesianStateforwardKinematics (const JointPosition &jointPositions) const
 Compute forward kinematics for given joint positions.
 
std::future< std::optional< RobotArmCartesianState > > forwardKinematicsAsync (const JointPosition &jointPositions) const
 
void forwardKinematicsAsync (std::function< void(const std::optional< RobotArmCartesianState > &)> callback, const JointPosition &jointPositions)
 
InverseKinematicsSolution inverseKinematics (const isom3 &world_T_effector_goal, JointPosition init={}) const
 Compute inverse kinematics for a desired end effector pose.
 
InverseKinematicsSolution inverseKinematics (const std::map< std::string, isom3 > &world_T_endpoints_goal, JointPosition init={}) const
 
void inverseKinematicsAsync (std::function< void(const std::optional< InverseKinematicsSolution > &)> callback, const isom3 &world_T_effector_goal, const JointPosition &init={}) const
 
void inverseKinematicsAsync (std::function< void(const std::optional< InverseKinematicsSolution > &)> callback, const std::map< std::string, isom3 > &world_T_endpoints_goal, const JointPosition &init={}) const
 
InverseKinematicsVelSolution inverseKinematicsVel (const mat4 &goalVelocity, const JointPosition &jointPosition) const
 Compute inverse kinematics for a desired end effector velocity.
 
InverseKinematicsVelSolution inverseKinematicsVel (const vec3 &goalTranslVelocity, const vec3 &goalRotVelocity, const JointPosition &jointPosition) const
 Compute inverse kinematics for a desired end effector translational and rotational velocity.
 
JacobianSolution computeJacobian (const JointPosition &jointPosition) const
 Compute the Jacobian matrix at given joint positions.
 
std::shared_ptr< TrackingSequencecreateTrajectory (const std::vector< JointPosition > &trajectory, const std::vector< double > &timestamps) const
 Create a tracking sequence by computing forward kinematics for each joint position in the trajectory, storing both the joint trajectory as a component and the corresponding end-effector poses with timestamps.
 
const std::vector< AttachedObject > & attachedObjects () const
 Additional effector meshes that can be added at stream configuration.
 
void addAttachedObject (const AttachedObject &attachedObject)
 
isom3 flange_T_effector () const
 Get the active end-effector-to-flange transformation.
 
std::optional< isom3 > flange_T_effector_override () const
 Get the active end-effector-to-flange transformation that overrides the end-effector defined in the Robot Model or the original URDF file.
 
void set_flange_T_effector_override (const std::optional< isom3 > &newValue={})
 Sets or clears the override end-effector-to-flange transformation, allowing runtime modification of the tool center point (TCP).
 
isom3 world_T_base () const
 Get the transformation from world to robot base.
 
void set_world_T_base (const isom3 &newValue)
 Sets the transformation from world to robot base.
 
std::optional< isom3 > flange_T_usprobe () const
 Optional transform from the flange to the ultrasound probe according the US module convention.
 
- Public Member Functions inherited from Configurable
virtual void configureDefaults ()
 Retrieve the properties of this object, replaces values with their defaults and sets it again.
 
void registerParameter (ParameterBase *param)
 Register the given Parameter or SubProperty, so that it will be configured during configure()/configuration().
 
void unregisterParameter (const ParameterBase *param)
 Remove the given Parameter or SubProperty from the list of registered parameters.
 
 Configurable (const Configurable &rhs)
 
 Configurable (Configurable &&rhs) noexcept
 
Configurableoperator= (const Configurable &)
 
Configurableoperator= (Configurable &&) noexcept
 

Public Attributes

Signal< isom3 > signal_world_T_base_changed
 Signal emitted when the transformation from the world frame to the base frame changes.
 
Signal activeGroupChanged
 
Signal< std::optional< isom3 > > signal_flange_T_effector_changed
 Signal emitted when the transformation from the TCP transformation changes.
 
- Public Attributes inherited from Configurable
Signal signalParametersChanged
 Emitted whenever one of the registered Parameters' or SubPropertys' signalValueChanged signal was emitted.
 

Additional Inherited Members

- Protected Attributes inherited from Configurable
std::vector< Paramm_params
 List of all registered Parameter and SubProperty instances.
 

Member Function Documentation

◆ configure()

void configure ( const Properties * p)
overridevirtual

Initialize the robot instance's spatial setup and attached tools/objects.

Configure the transformations matrices:

  • robot base position in world coordinates (World_T_Base)
  • end-effector position relative to the flange (Flange_T_Effector)
  • ultrasound probe calibration (Flange_T_USProbe)
  • any additional attached objects and their corresponding transformations.

Reimplemented from Configurable.

◆ configuration()

void configuration ( Properties * p) const
overridevirtual

Retrieve the current robot instance properties into a Properties object for later persistence or serialization.

The parameters to be retrieved are:

  • robot base position in world coordinates (World_T_Base)
  • end-effector position relative to the flange (Flange_T_Effector)
  • ultrasound probe calibration (Flange_T_USProbe),
  • any additional attached objects and their corresponding transformations.

Reimplemented from Configurable.

◆ robotModel()

std::shared_ptr< const RobotModel > robotModel ( ) const
inline

Access to the robot's kinematic and dynamic model.

Returns
- Valid pointer if robot model exists
  • nullptr if no robot model exist (incorrect initialization of the RobotInstance class)

◆ robotModelRef()

const RobotModel * robotModelRef ( ) const
inline

Read-only access to the robot's kinematic and dynamic model.

Returns
non-owning pointer to the robot model
  • Valid pointer if robot instance exists
  • nullptr if no robot instance is available

◆ forwardKinematics()

std::optional< RobotArmCartesianState > forwardKinematics ( const JointPosition & jointPositions) const

Compute forward kinematics for given joint positions.

Parameters
jointPositions- current joint positions.
Returns
an optional variable that represents the complete cartesian state of a robot arm including transformations for all links, attached objects, flange, and end effector relative to the robot's base frame (
See also
Common).

◆ inverseKinematics()

InverseKinematicsSolution inverseKinematics ( const isom3 & world_T_effector_goal,
JointPosition init = {} ) const

Compute inverse kinematics for a desired end effector pose.

Parameters
world_T_effector_goalDesired end effector pose in world coordinates.
initInitial joint positions for IK solver.
Returns
container for robot computation results that includes an optional value, error metric, and status indicating success, failure, or invalid input (
See also
RobotModel) representing the inverse kinematics solution.
Note
the computation is performed by transforming the world-space effector goal into the robot's original coordinate system, accounting for both robot repositioning and tool center point overrides.

◆ inverseKinematicsVel() [1/2]

InverseKinematicsVelSolution inverseKinematicsVel ( const mat4 & goalVelocity,
const JointPosition & jointPosition ) const

Compute inverse kinematics for a desired end effector velocity.

Parameters
goalVelocityDesired end effector velocity as Eigen 4x4 matrix.
jointPositionCurrent joint positions.
Returns
container for robot computation results that includes an optional value, error metric, and status indicating success, failure, or invalid input (
See also
RobotModel) representing the inverse kinematics solution.
Note
The inverse velocity kinematics is performed by first transforming the desired end-effector velocity from world coordinates. to the robot's original flange frame, accounting for both robot positioning and tool center point overrides.

◆ inverseKinematicsVel() [2/2]

InverseKinematicsVelSolution inverseKinematicsVel ( const vec3 & goalTranslVelocity,
const vec3 & goalRotVelocity,
const JointPosition & jointPosition ) const

Compute inverse kinematics for a desired end effector translational and rotational velocity.

Parameters
goalTranslVelocityDesired translational velocity as Eigen 3x1 matrix.
goalRotVelocityDesired end effector velocity as Eigen 3x1 matrix.
jointPositionCurrent joint positions.
Returns
container for robot computation results that includes an optional value, error metric, and status indicating success, failure, or invalid input (
See also
RobotModel) representing the inverse kinematics solution.
Note
the inverse velocity kinematics is performed by first transforming the desired end-effector velocity from world coordinates. to the robot's original flange frame, accounting for both robot positioning and tool center point overrides.

◆ computeJacobian()

JacobianSolution computeJacobian ( const JointPosition & jointPosition) const

Compute the Jacobian matrix at given joint positions.

Parameters
jointPositionCurrent joint positions.
Returns
A 6xN Eigen matrix representing the robot's Jacobian which maps N joint velocities to the 6D end-effector velocity (3D linear + 3D angular).

◆ createTrajectory()

std::shared_ptr< TrackingSequence > createTrajectory ( const std::vector< JointPosition > & trajectory,
const std::vector< double > & timestamps ) const

Create a tracking sequence by computing forward kinematics for each joint position in the trajectory, storing both the joint trajectory as a component and the corresponding end-effector poses with timestamps.

Parameters
trajectoryVector of joint positions.
timestampsVector of corresponding timestamps.
Returns
Sequence of rigid tracking data with optional timestamps.

◆ flange_T_effector()

isom3 flange_T_effector ( ) const

Get the active end-effector-to-flange transformation.

Returns
an Eigen isometric transformation matrix.
Note
The transformation can either be the robot model's original effector-to-flange transformation (which defaults to the identity transform), or a custom override that accounts for tool changes, calibration adjustments, or other modifications.

◆ flange_T_effector_override()

std::optional< isom3 > flange_T_effector_override ( ) const

Get the active end-effector-to-flange transformation that overrides the end-effector defined in the Robot Model or the original URDF file.

Returns
an Eigen isometric transformation matrix.

◆ set_flange_T_effector_override()

void set_flange_T_effector_override ( const std::optional< isom3 > & newValue = {})

Sets or clears the override end-effector-to-flange transformation, allowing runtime modification of the tool center point (TCP).

When modified, notifies listeners through signal_flange_T_effector_changed to handle updates like visualization or trajectory replanning.

◆ world_T_base()

isom3 world_T_base ( ) const

Get the transformation from world to robot base.

Returns
Eigen SE(3) isometric transformation matrix.

◆ set_world_T_base()

void set_world_T_base ( const isom3 & newValue)

Sets the transformation from world to robot base.

Parameters
newValueNew isometric transformation matrix
Note
Emits signal that the base-to-world transformation has changed

◆ flange_T_usprobe()

std::optional< isom3 > flange_T_usprobe ( ) const

Optional transform from the flange to the ultrasound probe according the US module convention.

If defined, it will be used to generate tracking data in RobotUSTrackingStream. Else, flange_T_effector will be used for that purpose (after adjusting the coordinate system to the convention expected by the US module) Get the usprobe-to-flange transformation, following ultrasound module conventions.

Member Data Documentation

◆ signal_world_T_base_changed

Signal<isom3> signal_world_T_base_changed

Signal emitted when the transformation from the world frame to the base frame changes.

The signal carries an Eigen isometric transformation representing the updated pose of the base in world coordinates.

◆ signal_flange_T_effector_changed

Signal<std::optional<isom3> > signal_flange_T_effector_changed

Signal emitted when the transformation from the TCP transformation changes.

The signal carries an optional Eigen isometric transformation representing the new tcp-to-flange transformation.

Note
The updated transformation will be applied in the next motion

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