5#include <franka/control_types.h>
24#pragma clang diagnostic push
25#pragma clang diagnostic ignored "-Wimplicit-conversion"
31#pragma clang diagnostic pop
76 return {transform * end_effector_pose_, elbow_state_};
86 return {end_effector_pose_ * transform, elbow_state_};
116 return end_effector_pose_;
131 Affine end_effector_pose_;
132 std::optional<ElbowState> elbow_state_;
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