![]() |
ImFusion SDK 4.3
|
#include <RoboticsPlugin/Include/ImFusion/Robotics/UR/URRobotState.h>
Extends RobotState adding fields for the Universal Robot analog IO. More...
Inheritance diagram for URRobotState:Extends RobotState adding fields for the Universal Robot analog IO.
Classes | |
| struct | AnalogIoState |
Public Member Functions | |
| URRobotState (const std::shared_ptr< const RobotModel > &modelRef) | |
| URRobotState (const RobotState &state) | |
| URRobotState (std::shared_ptr< const RobotInstance > instance, const JointState &jointState, const std::optional< CartesianFrames > &cartesianFrames, unsigned long long timeStamp, unsigned long long timestampArrival) | |
Public Member Functions inherited from RobotState | |
| 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 | |
| AnalogIoState | m_analogIoState |
Public Attributes inherited from RobotState | |
| 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 |
Additional Inherited Members | |
Protected Attributes inherited from RobotState | |
| 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. | |