ImFusion C++ SDK 4.4.0
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  ImFusion::Robotics::RobotLocation
 Base class for describing the parameters needed by the individual robot SDK to connect to a device. More...
struct  ImFusion::Robotics::RobotJointDescription
 Structs. More...
struct  ImFusion::Robotics::RobotLinkDescription
 Defines a description of a robot link including its visual properties and connections. More...
struct  ImFusion::Robotics::SavedGroupState
 Represents a named configuration of joint positions for a specific group of robot joints. More...
struct  ImFusion::Robotics::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  ImFusion::Robotics::RobotArmCartesianState
 Comprehensive description of the complete Cartesian state of a robot arm and its attached objects. More...
class  ImFusion::Robotics::RobotGUIProperties
class  ImFusion::Robotics::RobotInstance
 A class that manages a robot's kinematic model and coordinate transformations in the ImFusion SDK. More...
class  ImFusion::Robotics::RobotRunner
 Core class for managing robot execution and real-time control in the ImFusion SDK. More...
struct  ImFusion::Robotics::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  ImFusion::Robotics::JointState
 Represents a joint's rotational state in terms of position and velocity. More...
struct  ImFusion::Robotics::CartesianQuantities
 Represents Cartesian quantities used to describe 3D spatial information. More...
struct  ImFusion::Robotics::CartesianState
 Represents pose and velocity of a frame in Cartesian coordinates. More...
struct  ImFusion::Robotics::CartesianFrames
 Holds two Cartesian States between different parts of the robotic system (i.e flange to base, and effector to base). More...
class  ImFusion::Robotics::RobotState
 Contains the current status of the robot (i.e. More...
class  ImFusion::Robotics::RobotStateStreamData
 Stream data containing robot state information. More...
class  ImFusion::Robotics::RobotStateStream
 A Stream class for interfacing with robots in the ImFusion SDK. More...

Typedefs

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

Enumerations

enum class  ImFusion::Robotics::ReferenceFrame { ReferenceFrame::World , ReferenceFrame::Base , ReferenceFrame::Flange , ReferenceFrame::Effector }
 Defines the reference frame for robot coordinate transformations. More...
enum class  ImFusion::Robotics::Axis { X , Y , Z }
 Defines the Cartesian axes for robot movements.
enum class  ImFusion::Robotics::RobotStreamType { RobotStreamType::Simulated , RobotStreamType::State , Control }
 Defines the type of robot data stream. More...

Functions

bool ImFusion::Robotics::hasRealtimeKernel ()
 Check if the operating system supports (soft) real-time capabilities.
bool ImFusion::Robotics::makeCurrentThreadSoftRealtime ()
 Configure the current thread for real-time control.
isom3 ImFusion::Robotics::urdfPoseToImFusionMatrix (const urdf::Pose &pose)
 Convert URDF-style pose to ImFusion matrix format and handle unit conversion from meters to millimeters automatically.
isom3 ImFusion::Robotics::computeVelocity (double periodMs, const isom3 &delta)
 Compute the velocity matrix, corresponding to the movement of the object over a second.
isom3 ImFusion::Robotics::computeDisplacement (double periodMs, const isom3 &delta)
 Compute displacement matrix, corresponding to the movement of the object over a second.
isom3 ImFusion::Robotics::exponentialSmoothing (double alpha, const isom3 &newData, const isom3 &oldData)
 Performs an exponential smoothing between two poses.
isom3 ImFusion::Robotics::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.
void ImFusion::Robotics::vectorToJointArray (const std::vector< float > &vec, KDL::JntArray &outArr)
 Convert a vector of floats to a KDL::JntArray.
void ImFusion::Robotics::jointArrayToVector (const KDL::JntArray &arr, std::vector< float > &outVec)
 Convert a KDL::JntArray to vector of floats.
void ImFusion::Robotics::vectorToJointArray (const std::vector< double > &vec, KDL::JntArray &outArr)
 Convert a vector of doubles to a KDL::JntArray.
void ImFusion::Robotics::jointArrayToVector (const KDL::JntArray &arr, std::vector< double > &outVec)
 Convert a KDL::JntArray to vector of doubles.
template<typename VectorType>
JointQuantity ImFusion::Robotics::vectorToJointQuantity (const VectorType &v)
template<typename VectorType>
void ImFusion::Robotics::vectorToJointQuantity (const VectorType &v, JointQuantity &jq)
template<typename VectorType>
VectorType ImFusion::Robotics::jointQuantityToVector (const JointQuantity &jq)
template<typename VectorType>
void ImFusion::Robotics::jointQuantityToVector (const JointQuantity &jq, VectorType &v)
void ImFusion::Robotics::jointQuantityToKDLArray (const JointQuantity &jq, KDL::JntArray &kdlArray)
void ImFusion::Robotics::vectorToJointArray (const JointPosition &vec, KDL::JntArray &outArr)
void ImFusion::Robotics::jointArrayToVector (const KDL::JntArray &arr, JointPosition &outVec)
std::optional< double > ImFusion::Robotics::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::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::stringImFusion::Robotics::ReferenceFrameNames

Enumeration Type Documentation

◆ ReferenceFrame

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

Defines the reference frame for robot coordinate transformations.

Enumerator
World 

ImFusion world frame.

Base 

Robot base frame.

Flange 

Robot flange frame (last joint).

Effector 

Robot effector frame (tool center point).

◆ RobotStreamType

#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()

bool ImFusion::Robotics::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()

bool ImFusion::Robotics::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()

isom3 ImFusion::Robotics::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()

isom3 ImFusion::Robotics::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()

isom3 ImFusion::Robotics::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()

isom3 ImFusion::Robotics::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()

isom3 ImFusion::Robotics::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]

void ImFusion::Robotics::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]

void ImFusion::Robotics::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]

void ImFusion::Robotics::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]

void ImFusion::Robotics::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::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::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> ImFusion::Robotics::ReferenceFrameNames

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

Initial value:
= {{ReferenceFrame::World, "World"},
{ReferenceFrame::Effector, "Effector"}}
@ Base
Robot base frame.
Definition Common.h:61
@ Flange
Robot flange frame (last joint).
Definition Common.h:62
@ Effector
Robot effector frame (tool center point).
Definition Common.h:63
@ World
ImFusion world frame.
Definition Common.h:60
Search Tab / S to search, Esc to close