Franky 1.1.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 <franka/control_types.h>
4
5#include <Eigen/Core>
6#include <optional>
7
9#include "franky/types.hpp"
10
11namespace franky {
12
19class RobotPose {
20 public:
21 RobotPose();
22
24
25 // Suppress implicit conversion warning
26#pragma clang diagnostic push
27#pragma clang diagnostic ignored "-Wimplicit-conversion"
32 RobotPose(Affine end_effector_pose, std::optional<ElbowState> elbow_state = std::nullopt);
33#pragma clang diagnostic pop
34
41 explicit RobotPose(
43
48 explicit RobotPose(const Vector6d &vector_repr, std::optional<ElbowState> elbow_state = std::nullopt);
49
53 explicit RobotPose(const franka::CartesianPose &franka_pose);
54
62 [[nodiscard]] Vector7d vector_repr() const;
63
71 [[nodiscard]] franka::CartesianPose as_franka_pose(
73
81 [[nodiscard]] RobotPose leftTransform(const Affine &transform) const {
82 return {transform * end_effector_pose_, elbow_state_};
83 }
84
92 [[nodiscard]] RobotPose rightTransform(const Affine &transform) const {
93 return {end_effector_pose_ * transform, elbow_state_};
94 }
95
104 [[nodiscard]] RobotPose changeEndEffectorFrame(const Affine &transform) const { return rightTransform(transform); }
105
112 [[nodiscard]] RobotPose withElbowState(const std::optional<ElbowState> elbow_state) const {
113 return {end_effector_pose_, elbow_state};
114 }
115
121 [[nodiscard]] Affine end_effector_pose() const { return end_effector_pose_; }
122
128 [[nodiscard]] std::optional<ElbowState> elbow_state() const { return elbow_state_; }
129
130 friend std::ostream &operator<<(std::ostream &os, const RobotPose &robot_pose);
131
132 private:
133 Affine end_effector_pose_;
134 std::optional<ElbowState> elbow_state_;
135};
136
138 return robot_pose.rightTransform(right_transform);
139}
140
142 return robot_pose.leftTransform(left_transform);
143}
144
145} // namespace franky
Cartesian pose of a robot.
Definition robot_pose.hpp:19
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:104
RobotPose()
Definition robot_pose.cpp:51
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:34
RobotPose withElbowState(const std::optional< ElbowState > elbow_state) const
Get the pose with a new elbow state.
Definition robot_pose.hpp:112
franka::CartesianPose as_franka_pose(FlipDirection default_elbow_flip_direction=FlipDirection::kNegative) const
Convert this pose to a franka pose.
Definition robot_pose.cpp:43
friend std::ostream & operator<<(std::ostream &os, const RobotPose &robot_pose)
Definition robot_pose.cpp:53
Affine end_effector_pose() const
Get the end effector pose.
Definition robot_pose.hpp:121
std::optional< ElbowState > elbow_state() const
Get the elbow state.
Definition robot_pose.hpp:128
RobotPose leftTransform(const Affine &transform) const
Transform this pose with a given affine transformation from the left side.
Definition robot_pose.hpp:81
RobotPose rightTransform(const Affine &transform) const
Transform this pose with a given affine transformation from the right side.
Definition robot_pose.hpp:92
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:76
Eigen::Vector< double, 7 > Vector7d
Definition types.hpp:11
Eigen::Vector< double, 6 > Vector6d
Definition types.hpp:10
FlipDirection
Flip direction of a joint.
Definition elbow_state.hpp:12
Eigen::Affine3d Affine
Definition types.hpp:15