Franky  0.9.1
A High-Level Motion API for Franka
Public Member Functions | 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< double > elbow_position=std::nullopt)
 
 RobotPose (const Vector7d &vector_repr, bool ignore_elbow=false)
 
 RobotPose (const Vector6d &vector_repr, std::optional< double > elbow_position=std::nullopt)
 
 RobotPose (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. More...
 
franka::CartesianPose as_franka_pose () const
 Convert this pose to a franka pose. More...
 
RobotPose leftTransform (const Affine &transform) const
 Transform this pose with a given affine transformation from the left side. More...
 
RobotPose rightTransform (const Affine &transform) const
 Transform this pose with a given affine transformation from the right side. More...
 
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). More...
 
RobotPose withElbowPosition (const std::optional< double > elbow_position) const
 Get the pose with a new elbow position. More...
 
Affine end_effector_pose () const
 Get the end effector pose. More...
 
std::optional< double > elbow_position () const
 Get the elbow position. More...
 

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< double >  elbow_position = std::nullopt 
)
Parameters
end_effector_poseThe pose of the end effector.
elbow_positionThe position of the elbow. Optional.

◆ RobotPose() [4/6]

franky::RobotPose::RobotPose ( const Vector7d vector_repr,
bool  ignore_elbow = false 
)
explicit
Parameters
vector_reprThe vector representation of the pose.
ignore_elbowWhether to ignore the elbow position. Default is false.

◆ RobotPose() [5/6]

franky::RobotPose::RobotPose ( const Vector6d vector_repr,
std::optional< double >  elbow_position = std::nullopt 
)
explicit
Parameters
vector_reprThe vector representation of the pose.
elbow_positionThe position of the elbow. Optional.

◆ RobotPose() [6/6]

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

Member Function Documentation

◆ as_franka_pose()

franka::CartesianPose franky::RobotPose::as_franka_pose ( ) const

Convert this pose to a franka pose.

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_position()

std::optional<double> franky::RobotPose::elbow_position ( ) const
inline

Get the elbow position.

Returns
The elbow position.

◆ 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.

Returns
The vector representation of the pose.

◆ withElbowPosition()

RobotPose franky::RobotPose::withElbowPosition ( const std::optional< double >  elbow_position) const
inline

Get the pose with a new elbow position.

Parameters
elbow_positionThe new elbow position.
Returns
The pose with the new elbow position.

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