Franky 0.12.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
Public Member Functions | Friends | List of all members
franky::RobotPose Class Reference

Cartesian pose of a robot. More...

#include <robot_pose.hpp>

Public Member Functions

 RobotPose ()
 
 RobotPose (const RobotPose &robot_pose)
 
 RobotPose (Affine end_effector_pose, std::optional< ElbowState > elbow_state=std::nullopt)
 
 RobotPose (const Vector7d &vector_repr, bool ignore_elbow=false, FlipDirection flip_direction=FlipDirection::kNegative)
 
 RobotPose (const Vector6d &vector_repr, std::optional< ElbowState > elbow_state=std::nullopt)
 
 RobotPose (const franka::CartesianPose &franka_pose)
 
Vector7d vector_repr () const
 Get the vector representation of the pose, which consists of the end effector position and orientation (as rotation vector) and the elbow position. Does not contain the flip component of the elbow state.
 
franka::CartesianPose as_franka_pose (FlipDirection default_elbow_flip_direction=FlipDirection::kNegative) const
 Convert this pose to a franka pose.
 
RobotPose leftTransform (const Affine &transform) const
 Transform this pose with a given affine transformation from the left side.
 
RobotPose rightTransform (const Affine &transform) const
 Transform this pose with a given affine transformation from the right side.
 
RobotPose changeEndEffectorFrame (const Affine &transform) const
 Change the frame of the end effector by applying a transformation from the right side. This is equivalent to calling rightTransform(transform).
 
RobotPose withElbowState (const std::optional< ElbowState > elbow_state) const
 Get the pose with a new elbow state.
 
Affine end_effector_pose () const
 Get the end effector pose.
 
std::optional< ElbowStateelbow_state () const
 Get the elbow state.
 

Friends

std::ostream & operator<< (std::ostream &os, const RobotPose &robot_pose)
 

Detailed Description

Cartesian pose of a robot.

This class encapsulates the cartesian pose of a robot, which comprises the end effector pose and the elbow position.

Constructor & Destructor Documentation

◆ RobotPose() [1/6]

franky::RobotPose::RobotPose ( )

◆ RobotPose() [2/6]

franky::RobotPose::RobotPose ( const RobotPose robot_pose)
default

◆ RobotPose() [3/6]

franky::RobotPose::RobotPose ( Affine  end_effector_pose,
std::optional< ElbowState elbow_state = std::nullopt 
)
Parameters
end_effector_poseThe pose of the end effector.
elbow_stateThe state of the elbow. Optional.

◆ RobotPose() [4/6]

franky::RobotPose::RobotPose ( const Vector7d vector_repr,
bool  ignore_elbow = false,
FlipDirection  flip_direction = FlipDirection::kNegative 
)
explicit
Parameters
vector_reprThe vector representation of the pose.
ignore_elbowWhether to ignore the elbow state. Default is false.
flip_directionThe flip direction to use if the elbow is not ignored. Default is negative.

◆ RobotPose() [5/6]

franky::RobotPose::RobotPose ( const Vector6d vector_repr,
std::optional< ElbowState elbow_state = std::nullopt 
)
explicit
Parameters
vector_reprThe vector representation of the pose.
elbow_stateThe state of the elbow. Optional.

◆ RobotPose() [6/6]

franky::RobotPose::RobotPose ( const franka::CartesianPose &  franka_pose)
explicit
Parameters
franka_poseThe franka pose.

Member Function Documentation

◆ as_franka_pose()

franka::CartesianPose franky::RobotPose::as_franka_pose ( FlipDirection  default_elbow_flip_direction = FlipDirection::kNegative) const

Convert this pose to a franka pose.

Parameters
default_elbow_flip_directionThe default flip direction to use if the elbow flip direction is not set.
Returns
The franka pose.

◆ changeEndEffectorFrame()

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

Change the frame of the end effector by applying a transformation from the right side. This is equivalent to calling rightTransform(transform).

Parameters
transformThe transform to apply.
Returns
The robot pose with the new end effector frame.

◆ elbow_state()

std::optional< ElbowState > franky::RobotPose::elbow_state ( ) const
inline

Get the elbow state.

Returns
The elbow state.

◆ end_effector_pose()

Affine franky::RobotPose::end_effector_pose ( ) const
inline

Get the end effector pose.

Returns
The end effector pose.

◆ leftTransform()

RobotPose franky::RobotPose::leftTransform ( const Affine transform) const
inline

Transform this pose with a given affine transformation from the left side.

Parameters
transformThe transform to apply.
Returns
The transformed robot pose.

◆ rightTransform()

RobotPose franky::RobotPose::rightTransform ( const Affine transform) const
inline

Transform this pose with a given affine transformation from the right side.

Parameters
transformThe transform to apply.
Returns
The transformed robot pose.

◆ vector_repr()

Vector7d franky::RobotPose::vector_repr ( ) const

Get the vector representation of the pose, which consists of the end effector position and orientation (as rotation vector) and the elbow position. Does not contain the flip component of the elbow state.

Returns
The vector representation of the pose.

◆ withElbowState()

RobotPose franky::RobotPose::withElbowState ( const std::optional< ElbowState elbow_state) const
inline

Get the pose with a new elbow state.

Parameters
elbow_stateThe new elbow state.
Returns
The pose with the new elbow state.

Friends And Related Symbol Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream &  os,
const RobotPose robot_pose 
)
friend

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