Franky  0.9.1
A High-Level Motion API for Franka
cartesian_state.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <optional>
4 #include <Eigen/Core>
5 
6 #include "franky/robot_pose.hpp"
8 
9 namespace franky {
10 
11 /*
12  * @brief Cartesian state of a robot.
13  *
14  * This class encapsulates the cartesian state of a robot, which comprises the end effector pose and the end effector
15  * velocity.
16  */
18  public:
19  // Suppress implicit conversion warning
20 #pragma clang diagnostic push
21 #pragma clang diagnostic ignored "-Wimplicit-conversion"
22  CartesianState(const RobotPose &pose) : pose_(pose) {}
23 #pragma clang diagnostic pop
24 
30  : pose_(pose), velocity_(velocity) {}
31 
32  CartesianState(const CartesianState &) = default;
33 
34  CartesianState() = default;
35 
42  [[nodiscard]] inline CartesianState transformWith(const Affine &transform) const {
43  return {transform * pose_, transform * velocity_};
44  }
45 
52  [[nodiscard]] CartesianState changeEndEffectorFrame(const Affine &transform) const {
53  auto offset_world_frame = pose_.end_effector_pose() * transform.translation();
54  return {pose_.changeEndEffectorFrame(transform), velocity_.changeEndEffectorFrame(offset_world_frame)};
55  }
56 
57  /*
58  * @brief Pose component of the state.
59  */
60  [[nodiscard]] inline RobotPose pose() const {
61  return pose_;
62  }
63 
64  /*
65  * @brief Velocity component of the state.
66  */
67  [[nodiscard]] inline RobotVelocity velocity() const {
68  return velocity_;
69  }
70 
71  private:
72  RobotPose pose_;
73  RobotVelocity velocity_;
74 };
75 
76 inline CartesianState operator*(const Affine &transform, const CartesianState &cartesian_state) {
77  return cartesian_state.transformWith(transform);
78 }
79 
80 } // namespace franky
Definition: cartesian_state.hpp:17
CartesianState(const RobotPose &pose, const RobotVelocity &velocity)
Definition: cartesian_state.hpp:29
RobotPose pose() const
Definition: cartesian_state.hpp:60
CartesianState(const RobotPose &pose)
Definition: cartesian_state.hpp:22
CartesianState changeEndEffectorFrame(const Affine &transform) const
Change the end effector frame of the state by the given affine transform.
Definition: cartesian_state.hpp:52
CartesianState transformWith(const Affine &transform) const
Transform the frame of the state by applying the given affine transform.
Definition: cartesian_state.hpp:42
CartesianState(const CartesianState &)=default
RobotVelocity velocity() const
Definition: cartesian_state.hpp:67
Cartesian pose of a robot.
Definition: robot_pose.hpp:16
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:91
Affine end_effector_pose() const
Get the end effector pose.
Definition: robot_pose.hpp:110
Cartesian velocity of a robot.
Definition: robot_velocity.hpp:18
RobotVelocity changeEndEffectorFrame(const Eigen::Vector3d &offset_world_frame) const
Change the end-effector frame by adding the given offset to the current end-effector frame....
Definition: robot_velocity.hpp:87
Definition: gripper.cpp:3
CartesianState operator*(const Affine &transform, const CartesianState &cartesian_state)
Definition: cartesian_state.hpp:76
Eigen::Affine3d Affine
Definition: types.hpp:13