Franky 0.12.0
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< 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< ElbowState > | elbow_state () const |
Get the elbow state. | |
Friends | |
std::ostream & | operator<< (std::ostream &os, const RobotPose &robot_pose) |
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 | ( | ) |
franky::RobotPose::RobotPose | ( | Affine | end_effector_pose, |
std::optional< ElbowState > | elbow_state = std::nullopt |
||
) |
end_effector_pose | The pose of the end effector. |
elbow_state | The state of the elbow. Optional. |
|
explicit |
vector_repr | The vector representation of the pose. |
ignore_elbow | Whether to ignore the elbow state. Default is false. |
flip_direction | The flip direction to use if the elbow is not ignored. Default is negative. |
|
explicit |
vector_repr | The vector representation of the pose. |
elbow_state | The state of the elbow. Optional. |
|
explicit |
franka_pose | The franka pose. |
franka::CartesianPose franky::RobotPose::as_franka_pose | ( | FlipDirection | default_elbow_flip_direction = FlipDirection::kNegative | ) | const |
Convert this pose to a franka pose.
default_elbow_flip_direction | The default flip direction to use if the elbow flip direction is not set. |
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 state.
|
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. Does not contain the flip component of the elbow state.
|
inline |
Get the pose with a new elbow state.
elbow_state | The new elbow state. |