![]() |
ImFusion SDK 4.3
|
#include <RoboticsPlugin/Include/ImFusion/Robotics/RobotState.h>
Contains the current status of the robot (i.e. More...
Inheritance diagram for RobotState: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< RobotArmCartesianState > | cartesianState () const |
| attempts computing the FK and returns a reference if successful | |
| const JointState & | jointState () const |
| const CartesianFrames * | cartesianFrames () 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 RobotInstance > | robotInstance () const |
| const RobotInstance * | robotInstanceRef () 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 NativeRobotStateBase > | m_nativeRobotState |
Protected Attributes | |
| std::shared_ptr< const RobotInstance > | m_robotInstance |
| Geometric representation of the robot's structure. | |
| JointState | m_jointState |
| Joint positions as reported by the robot firmware. | |
| std::optional< CartesianFrames > | m_cartesianFrames |
| Cartesian poses of notable frames as reported by the robot firmware (if supported) | |
| std::optional< RobotArmCartesianState > | m_cartesianState |
| State computed lazily using forward kinematics. | |
|
explicit |
Initialize robot state where all joint values are set to zero.
| instance | encapsulates 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 | ( | 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.
| instance | encapsulates 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. |
| jointState | the joint states of the robot. The vector size must match the instance model's expected size. In case of mismatch an error is logged. |
| cartesianFrames | notable frames as reported by the robot firmware. |
| timeStamp | timestamp in milliseconds (for compatibility with the rest of the SDK), as reported by the robot firmware. |
| timestampArrival | timestamp in milliseconds (for compatibility with the rest of the SDK), reporting the first time the information reached the SDK boundary. |
| std::optional< isom3 > base_T_effector | ( | ) | const |
Retrieve the transformation end-effector-to-base.
| std::optional< isom3 > world_T_namedLink | ( | const std::string & | linkName | ) | const |
Retrieve the transformation from a particularly named link to the world.
| 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).