Franky
0.9.1
A High-Level Motion API for Franka
|
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... | |
Cartesian pose of a robot.
This class encapsulates the cartesian pose of a robot, which comprises the end effector pose and the elbow position.
franky::RobotPose::RobotPose | ( | ) |
|
default |
franky::RobotPose::RobotPose | ( | Affine | end_effector_pose, |
std::optional< double > | elbow_position = std::nullopt |
||
) |
end_effector_pose | The pose of the end effector. |
elbow_position | The position of the elbow. Optional. |
|
explicit |
vector_repr | The vector representation of the pose. |
ignore_elbow | Whether to ignore the elbow position. Default is false. |
|
explicit |
vector_repr | The vector representation of the pose. |
elbow_position | The position of the elbow. Optional. |
|
explicit |
franka_pose | The franka pose. |
franka::CartesianPose franky::RobotPose::as_franka_pose | ( | ) | const |
Convert this pose to a franka pose.
Change the frame of the end effector by applying a transformation from the right side. This is equivalent to calling rightTransform(transform).
transform | The transform to apply. |
|
inline |
Get the elbow position.
|
inline |
Get the end effector pose.
Transform this pose with a given affine transformation from the left side.
transform | The transform to apply. |
Transform this pose with a given affine transformation from the right side.
transform | The transform to apply. |
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.
|
inline |
Get the pose with a new elbow position.
elbow_position | The new elbow position. |