Franky  0.9.1
A High-Level Motion API for Franka
Public Member Functions | List of all members
franky::CartesianState Class Reference

#include <cartesian_state.hpp>

Public Member Functions

 CartesianState (const RobotPose &pose)
 
 CartesianState (const RobotPose &pose, const RobotVelocity &velocity)
 
 CartesianState (const CartesianState &)=default
 
 CartesianState ()=default
 
CartesianState transformWith (const Affine &transform) const
 Transform the frame of the state by applying the given affine transform. More...
 
CartesianState changeEndEffectorFrame (const Affine &transform) const
 Change the end effector frame of the state by the given affine transform. More...
 
RobotPose pose () const
 
RobotVelocity velocity () const
 

Constructor & Destructor Documentation

◆ CartesianState() [1/4]

franky::CartesianState::CartesianState ( const RobotPose pose)
inline

◆ CartesianState() [2/4]

franky::CartesianState::CartesianState ( const RobotPose pose,
const RobotVelocity velocity 
)
inline
Parameters
poseThe pose of the end effector.
velocityThe velocity of the end effector.

◆ CartesianState() [3/4]

franky::CartesianState::CartesianState ( const CartesianState )
default

◆ CartesianState() [4/4]

franky::CartesianState::CartesianState ( )
default

Member Function Documentation

◆ changeEndEffectorFrame()

CartesianState franky::CartesianState::changeEndEffectorFrame ( const Affine transform) const
inline

Change the end effector frame of the state by the given affine transform.

Parameters
transformThe pose of the new end-effector in the frame of the old end-effector.
Returns
The state with a new end-effector frame.

◆ pose()

RobotPose franky::CartesianState::pose ( ) const
inline

◆ transformWith()

CartesianState franky::CartesianState::transformWith ( const Affine transform) const
inline

Transform the frame of the state by applying the given affine transform.

Parameters
transformThe transformation to apply.
Returns
The state after the transformation.

◆ velocity()

RobotVelocity franky::CartesianState::velocity ( ) const
inline

The documentation for this class was generated from the following file: