ImFusion SDK 4.3
Robotics plugin

Functionality for robot control. More...

+ Collaboration diagram for Robotics plugin:

Detailed Description

Functionality for robot control.

Namespaces

namespace  ImFusion::Robotics::SupportedRobotTypes
 Robot names (types) as defined in the ImFusionSuite.
 

Classes

struct  RobotLocation
 Base class for describing the parameters needed by the individual robot SDK to connect to a device. More...
 
struct  RobotJointDescription
 Structs. More...
 
struct  RobotLinkDescription
 Defines a description of a robot link including its visual properties and connections. More...
 
struct  SavedGroupState
 Represents a named configuration of joint positions for a specific group of robot joints. More...
 
struct  RobotDescription
 Comprehensive description of a robot's kinematic structure and properties Contains the complete definition of a robot's joints, links, and their relationships. More...
 
struct  RobotArmCartesianState
 Comprehensive description of the complete Cartesian state of a robot arm and its attached objects. More...
 
class  RobotGUIProperties
 
class  RobotInstance
 A class that manages a robot's kinematic model and coordinate transformations in the ImFusion SDK. More...
 
class  RobotRunner
 Core class for managing robot execution and real-time control in the ImFusion SDK. More...
 
struct  JointQuantities
 Represents joint-related values (position, velocity, acceleration, torque, etc.) and their corresponding states (measured, desired, or commanded) and provides access to each of these values through member variables. More...
 
struct  JointState
 Represents a joint's rotational state in terms of position and velocity. More...
 
struct  CartesianQuantities
 Represents Cartesian quantities used to describe 3D spatial information. More...
 
struct  CartesianState
 Represents pose and velocity of a frame in Cartesian coordinates. More...
 
struct  CartesianFrames
 Holds two Cartesian States between different parts of the robotic system (i.e flange to base, and effector to base) More...
 
class  RobotState
 Contains the current status of the robot (i.e. More...
 
class  RobotStateStreamData
 Stream data containing robot state information. More...
 
class  RobotStateStream
 A Stream class for interfacing with robots in the ImFusion SDK. More...
 

Typedefs

using RobotType = std::string
 Unique identifier for the robot make, model and hardware configuration.
 
using JointQuantity = Eigen::VectorXd
 
using JointPosition = JointQuantity
 Position of each joint; the interpretation depends on the robot type.
 
using JointVelocity = JointQuantity
 Velocity of each joint; the interpretation depends on the robot type.
 
using JointTorques = JointQuantity
 Torque in Nm about each robot joint.
 
using Wrench = vec6
 Cartesian forces along each axis in N, and torques about each axis in Nm.
 
using JacobianMatrix = Eigen::Matrix<double, 6, Eigen::Dynamic>
 
using LinkPosition = std::map<std::string, isom3>
 

Enumerations

enum class  RobotStreamType { Simulated , State , Control }
 Defines the type of robot data stream. More...
 

Functions

IMFUSION_ROBOTICS_API bool hasRealtimeKernel ()
 Check if the operating system supports (soft) real-time capabilities.
 
IMFUSION_ROBOTICS_API bool makeCurrentThreadSoftRealtime ()
 Configure the current thread for real-time control.
 
IMFUSION_ROBOTICS_API isom3 urdfPoseToImFusionMatrix (const urdf::Pose &pose)
 Convert URDF-style pose to ImFusion matrix format and handle unit conversion from meters to millimeters automatically.
 
IMFUSION_ROBOTICS_API isom3 computeVelocity (double periodMs, const isom3 &delta)
 Compute the velocity matrix, corresponding to the movement of the object over a second.
 
IMFUSION_ROBOTICS_API isom3 computeDisplacement (double periodMs, const isom3 &delta)
 Compute displacement matrix, corresponding to the movement of the object over a second.
 
IMFUSION_ROBOTICS_API isom3 exponentialSmoothing (double alpha, const isom3 &newData, const isom3 &oldData)
 Performs an exponential smoothing between two poses.
 
IMFUSION_ROBOTICS_API isom3 tfPoseToImFusionMatrix (const vec3 &translationMeters, const vec4 &xyzwQuaternion)
 Convert ROS/tf-style pose to ImFusion matrix format and handle unit conversion from meters to millimeters automatically.
 
IMFUSION_ROBOTICS_API void vectorToJointArray (const std::vector< float > &vec, KDL::JntArray &outArr)
 Convert a vector of floats to a KDL::JntArray.
 
IMFUSION_ROBOTICS_API void jointArrayToVector (const KDL::JntArray &arr, std::vector< float > &outVec)
 Convert a KDL::JntArray to vector of floats.
 
IMFUSION_ROBOTICS_API void vectorToJointArray (const std::vector< double > &vec, KDL::JntArray &outArr)
 Convert a vector of doubles to a KDL::JntArray.
 
IMFUSION_ROBOTICS_API void jointArrayToVector (const KDL::JntArray &arr, std::vector< double > &outVec)
 Convert a KDL::JntArray to vector of doubles.
 
template<typename VectorType>
JointQuantity vectorToJointQuantity (const VectorType &v)
 
template<typename VectorType>
void vectorToJointQuantity (const VectorType &v, JointQuantity &jq)
 
template<typename VectorType>
VectorType jointQuantityToVector (const JointQuantity &jq)
 
template<typename VectorType>
void jointQuantityToVector (const JointQuantity &jq, VectorType &v)
 
void jointQuantityToKDLArray (const JointQuantity &jq, KDL::JntArray &kdlArray)
 
IMFUSION_ROBOTICS_API void vectorToJointArray (const JointPosition &vec, KDL::JntArray &outArr)
 
IMFUSION_ROBOTICS_API void jointArrayToVector (const KDL::JntArray &arr, JointPosition &outVec)
 
std::optional< double > IMFUSION_ROBOTICS_API lInfError (const Eigen::Ref< const Eigen::MatrixXd > &m1, const Eigen::Ref< const Eigen::MatrixXd > &m2, double tol=1.0e-4)
 Return the infinite-norm relative error between two Eigen matrices/vectors.
 
bool IMFUSION_ROBOTICS_API lInfErrorAreEqual (const Eigen::Ref< const Eigen::MatrixXd > &m1, const Eigen::Ref< const Eigen::MatrixXd > &m2, double tol=1.0e-4)
 Return if two Eigen matrices/vectors are equal within a given tolerance.
 

Variables

const std::map< ReferenceFrame, std::stringReferenceFrameNames
 

Enumeration Type Documentation

◆ RobotStreamType

enum class RobotStreamType
strong

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

Defines the type of robot data stream.

This categorizes different sources of robot data, distinguishing between simulated data, real-time state information, and control commands.

Enumerator
Simulated 

Data generated from a simulated robot environment (e.g., for testing or validation).

State 

Read-only real-time state data from a physical robot, including sensor readings and joint states.

Function Documentation

◆ hasRealtimeKernel()

IMFUSION_ROBOTICS_API bool hasRealtimeKernel ( )

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

Check if the operating system supports (soft) real-time capabilities.

Returns
True on Windows. On Linux, returns true only if the kernel was compiled with the PREEMPT-RT patch set.

◆ makeCurrentThreadSoftRealtime()

IMFUSION_ROBOTICS_API bool makeCurrentThreadSoftRealtime ( )

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

Configure the current thread for real-time control.

Requests the operating system scheduler to assign the highest priority to the thread.

Returns
true if the operation succeeds, false otherwise.

◆ urdfPoseToImFusionMatrix()

IMFUSION_ROBOTICS_API isom3 urdfPoseToImFusionMatrix ( const urdf::Pose & pose)

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

Convert URDF-style pose to ImFusion matrix format and handle unit conversion from meters to millimeters automatically.

Parameters
poseposition vector in meters and rotation as quaternion [x,y,z,w] (URDF convention).
Returns
Eigen transformation matrix in ImFusion format (millimeters).

◆ computeVelocity()

IMFUSION_ROBOTICS_API isom3 computeVelocity ( double periodMs,
const isom3 & delta )

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

Compute the velocity matrix, corresponding to the movement of the object over a second.

Parameters
periodMsThe time period in milliseconds over which the displacement occurs.
deltaThe transformation representing the displacement over the given period.
Returns
The scaled isometric transformation representing the speed (displacement per second).
Note
Scales the rotation angle while preserving the axis of rotation and adjusts the translation proportionally using the inverse of the period in seconds.

◆ computeDisplacement()

IMFUSION_ROBOTICS_API isom3 computeDisplacement ( double periodMs,
const isom3 & delta )

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

Compute displacement matrix, corresponding to the movement of the object over a second.

Parameters
periodMsThe time period in milliseconds over which the displacement occurs.
deltaThe transformation representing the displacement over the given period.
Returns
The scaled isometric transformation representing the displacement (displacement per second).
Note
Scales the rotation angle while preserving the axis of rotation and proportionally adjusts the translation based on the period in seconds.

◆ exponentialSmoothing()

IMFUSION_ROBOTICS_API isom3 exponentialSmoothing ( double alpha,
const isom3 & newData,
const isom3 & oldData )

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

Performs an exponential smoothing between two poses.

Parameters
alphaSmoothing factor in [0,1]. Higher values reduce lag but increase noise sensitivity
newDataLatest pose measurements
oldDataPrevious smoothed pose
Returns
smoothed pose or identity if numerical issue occur
Note
uses separate scaling of rotation and translation components to ensure proper interpolation When alpha = 0, returns oldData, when alpha=1 returns newData

◆ tfPoseToImFusionMatrix()

IMFUSION_ROBOTICS_API isom3 tfPoseToImFusionMatrix ( const vec3 & translationMeters,
const vec4 & xyzwQuaternion )

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

Convert ROS/tf-style pose to ImFusion matrix format and handle unit conversion from meters to millimeters automatically.

Parameters
translationMetersposition vector in meters (ROS convention).
xyzwQuaternionrotation as quaternion [x,y,z,w] (ROS convention).
Returns
Eigen isometric transformation in ImFusion format (millimeters.

◆ vectorToJointArray() [1/2]

IMFUSION_ROBOTICS_API void vectorToJointArray ( const std::vector< float > & vec,
KDL::JntArray & outArr )

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

Convert a vector of floats to a KDL::JntArray.

Parameters
vecInput vector containing joint values.
outOutput joint array, resized to match the input vector size.
Note
The function assumes the input and the output are properly sized and accessible, and overwrites any existing contents of the out param.

◆ jointArrayToVector() [1/2]

IMFUSION_ROBOTICS_API void jointArrayToVector ( const KDL::JntArray & arr,
std::vector< float > & outVec )

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

Convert a KDL::JntArray to vector of floats.

Parameters
arrInput joint array.
outOutput vector, resized to match the input array size
Note
The function assumes the input and the output are properly sized and accessible, and overwrites any existing contents of the out param.

◆ vectorToJointArray() [2/2]

IMFUSION_ROBOTICS_API void vectorToJointArray ( const std::vector< double > & vec,
KDL::JntArray & outArr )

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

Convert a vector of doubles to a KDL::JntArray.

Parameters
vecInput vector containing joint values.
outOutput joint array, resized to match the input vector size.
Note
The function assumes the input and the output are properly sized and accessible, and overwrites any existing contents of the out param.

◆ jointArrayToVector() [2/2]

IMFUSION_ROBOTICS_API void jointArrayToVector ( const KDL::JntArray & arr,
std::vector< double > & outVec )

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

Convert a KDL::JntArray to vector of doubles.

Parameters
arrInput joint array.
outOutput vector, resized to match the input array size
Note
The function assumes the input and the output are properly sized and accessible, and overwrites any existing contents of the out param.

◆ lInfError()

std::optional< double > IMFUSION_ROBOTICS_API lInfError ( const Eigen::Ref< const Eigen::MatrixXd > & m1,
const Eigen::Ref< const Eigen::MatrixXd > & m2,
double tol = 1.0e-4 )

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

Return the infinite-norm relative error between two Eigen matrices/vectors.

Parameters
m1First matrix
m2Second matrix
tolTolerance for the infinite-norm of the matrices
Returns
empty in cas of NANs, otherwise returns the infinite-norm relative error between the two matrices

◆ lInfErrorAreEqual()

bool IMFUSION_ROBOTICS_API lInfErrorAreEqual ( const Eigen::Ref< const Eigen::MatrixXd > & m1,
const Eigen::Ref< const Eigen::MatrixXd > & m2,
double tol = 1.0e-4 )

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

Return if two Eigen matrices/vectors are equal within a given tolerance.

Parameters
m1First matrix
m2Second matrix
tolTolerance for the infinite-norm of the matrices
Returns
true if the infinite-norm relative error between the two matrices is less than tol

Variable Documentation

◆ ReferenceFrameNames

const std::map<ReferenceFrame, std::string> ReferenceFrameNames

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

Initial value:
= {{ReferenceFrame::World, "World"},
{ReferenceFrame::Base, "Base"},
{ReferenceFrame::Flange, "Flange"},
{ReferenceFrame::Effector, "Effector"}}
Search Tab / S to search, Esc to close