Franky 0.12.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
robot_pose.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <optional>
4#include <Eigen/Core>
5#include <franka/control_types.h>
6
7#include "franky/types.hpp"
9
10namespace franky {
11
17class RobotPose {
18 public:
19 RobotPose();
20
22
23 // Suppress implicit conversion warning
24#pragma clang diagnostic push
25#pragma clang diagnostic ignored "-Wimplicit-conversion"
30 RobotPose(Affine end_effector_pose, std::optional<ElbowState> elbow_state = std::nullopt);
31#pragma clang diagnostic pop
32
38 explicit RobotPose(
40
45 explicit RobotPose(const Vector6d &vector_repr, std::optional<ElbowState> elbow_state = std::nullopt);
46
50 explicit RobotPose(const franka::CartesianPose &franka_pose);
51
58 [[nodiscard]] Vector7d vector_repr() const;
59
66 [[nodiscard]] franka::CartesianPose as_franka_pose(
68
75 [[nodiscard]] RobotPose leftTransform(const Affine &transform) const {
76 return {transform * end_effector_pose_, elbow_state_};
77 }
78
85 [[nodiscard]] RobotPose rightTransform(const Affine &transform) const {
86 return {end_effector_pose_ * transform, elbow_state_};
87 }
88
96 [[nodiscard]] RobotPose changeEndEffectorFrame(const Affine &transform) const {
97 return rightTransform(transform);
98 }
99
106 [[nodiscard]] RobotPose withElbowState(const std::optional<ElbowState> elbow_state) const {
107 return {end_effector_pose_, elbow_state};
108 }
109
116 return end_effector_pose_;
117 }
118
124 [[nodiscard]] std::optional<ElbowState> elbow_state() const {
125 return elbow_state_;
126 }
127
128 friend std::ostream& operator<<(std::ostream& os, const RobotPose& robot_pose);
129
130 private:
131 Affine end_effector_pose_;
132 std::optional<ElbowState> elbow_state_;
133};
134
136 return robot_pose.rightTransform(right_transform);
137}
138
140 return robot_pose.leftTransform(left_transform);
141}
142
143} // namespace franky
Cartesian pose of a robot.
Definition robot_pose.hpp:17
RobotPose changeEndEffectorFrame(const Affine &transform) const
Change the frame of the end effector by applying a transformation from the right side....
Definition robot_pose.hpp:96
RobotPose()
Definition robot_pose.cpp:50
RobotPose(const RobotPose &robot_pose)
Vector7d vector_repr() const
Get the vector representation of the pose, which consists of the end effector position and orientatio...
Definition robot_pose.cpp:33
RobotPose withElbowState(const std::optional< ElbowState > elbow_state) const
Get the pose with a new elbow state.
Definition robot_pose.hpp:106
franka::CartesianPose as_franka_pose(FlipDirection default_elbow_flip_direction=FlipDirection::kNegative) const
Convert this pose to a franka pose.
Definition robot_pose.cpp:42
friend std::ostream & operator<<(std::ostream &os, const RobotPose &robot_pose)
Definition robot_pose.cpp:52
Affine end_effector_pose() const
Get the end effector pose.
Definition robot_pose.hpp:115
std::optional< ElbowState > elbow_state() const
Get the elbow state.
Definition robot_pose.hpp:124
RobotPose leftTransform(const Affine &transform) const
Transform this pose with a given affine transformation from the left side.
Definition robot_pose.hpp:75
RobotPose rightTransform(const Affine &transform) const
Transform this pose with a given affine transformation from the right side.
Definition robot_pose.hpp:85
Definition dynamics_limit.cpp:8
std::array< double, dims > toStdD(const Eigen::Matrix< double, dims, 1 > &vector)
Definition util.hpp:18
CartesianState operator*(const Affine &transform, const CartesianState &cartesian_state)
Definition cartesian_state.hpp:78
Eigen::Vector< double, 7 > Vector7d
Definition types.hpp:12
Eigen::Vector< double, 6 > Vector6d
Definition types.hpp:11
FlipDirection
Flip direction of a joint.
Definition elbow_state.hpp:12
Eigen::Affine3d Affine
Definition types.hpp:16