![]() |
ImFusion SDK 4.3
|
#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: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
It provides both high-level and low-level kinematics access: High-level world coordinate operations
Low-level base-coordinate operations (via Robot ModeL)
The RobotInstance class is typically shared between multiple components for:
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 RobotModel > | robotModel () const |
| Access to the robot's kinematic and dynamic model. | |
| const RobotModel * | robotModelRef () const |
| Read-only access to the robot's kinematic and dynamic model. | |
| std::shared_ptr< const RobotGroup > | activeGroup () const |
| bool | setActiveGroup (const std::string &name, const RobotState *prevState=nullptr) |
| bool | validJointPosition (const JointPosition &jointPosition) const |
| std::optional< RobotArmCartesianState > | forwardKinematics (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< TrackingSequence > | createTrajectory (const std::vector< JointPosition > &trajectory, const std::vector< double > ×tamps) 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 | |
| Configurable & | operator= (const Configurable &) |
| Configurable & | operator= (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< Param > | m_params |
| List of all registered Parameter and SubProperty instances. | |
|
overridevirtual |
Initialize the robot instance's spatial setup and attached tools/objects.
Configure the transformations matrices:
Reimplemented from Configurable.
|
overridevirtual |
Retrieve the current robot instance properties into a Properties object for later persistence or serialization.
The parameters to be retrieved are:
Reimplemented from Configurable.
|
inline |
Access to the robot's kinematic and dynamic model.
|
inline |
Read-only access to the robot's kinematic and dynamic model.
| std::optional< RobotArmCartesianState > forwardKinematics | ( | const JointPosition & | jointPositions | ) | const |
Compute forward kinematics for given joint positions.
| jointPositions | - current joint positions. |
| InverseKinematicsSolution inverseKinematics | ( | const isom3 & | world_T_effector_goal, |
| JointPosition | init = {} ) const |
Compute inverse kinematics for a desired end effector pose.
| world_T_effector_goal | Desired end effector pose in world coordinates. |
| init | Initial joint positions for IK solver. |
| InverseKinematicsVelSolution inverseKinematicsVel | ( | const mat4 & | goalVelocity, |
| const JointPosition & | jointPosition ) const |
Compute inverse kinematics for a desired end effector velocity.
| goalVelocity | Desired end effector velocity as Eigen 4x4 matrix. |
| jointPosition | Current joint positions. |
| InverseKinematicsVelSolution inverseKinematicsVel | ( | const vec3 & | goalTranslVelocity, |
| const vec3 & | goalRotVelocity, | ||
| const JointPosition & | jointPosition ) const |
Compute inverse kinematics for a desired end effector translational and rotational velocity.
| goalTranslVelocity | Desired translational velocity as Eigen 3x1 matrix. |
| goalRotVelocity | Desired end effector velocity as Eigen 3x1 matrix. |
| jointPosition | Current joint positions. |
| JacobianSolution computeJacobian | ( | const JointPosition & | jointPosition | ) | const |
Compute the Jacobian matrix at given joint positions.
| jointPosition | Current joint positions. |
| 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.
| 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).
When modified, notifies listeners through signal_flange_T_effector_changed to handle updates like visualization or trajectory replanning.
| 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.
| newValue | New isometric transformation matrix |
| 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.
| 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<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.