Franky 1.1.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
cartesian_state.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <Eigen/Core>
4#include <optional>
5
8
9namespace franky {
10
11/*
12 * @brief Cartesian state of a robot.
13 *
14 * This class encapsulates the cartesian state of a robot, which comprises the
15 * end effector pose and the end effector 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
29 CartesianState(const RobotPose &pose, const RobotVelocity &velocity) : pose_(pose), velocity_(velocity) {}
30
31 CartesianState(const CartesianState &) = default;
32
33 CartesianState() = default;
34
42 [[nodiscard]] CartesianState transformWith(const Affine &transform) const {
43 return {transform * pose_, transform * velocity_};
44 }
45
54 [[nodiscard]] CartesianState changeEndEffectorFrame(const Affine &transform) const {
55 auto offset_world_frame = pose_.end_effector_pose() * transform.translation();
56 return {pose_.changeEndEffectorFrame(transform), velocity_.changeEndEffectorFrame(offset_world_frame)};
57 }
58
59 /*
60 * @brief Pose component of the state.
61 */
62 [[nodiscard]] RobotPose pose() const { return pose_; }
63
64 /*
65 * @brief Velocity component of the state.
66 */
67 [[nodiscard]] RobotVelocity velocity() const { return velocity_; }
68
69 friend inline std::ostream &operator<<(std::ostream &os, const CartesianState &cartesian_state);
70
71 private:
72 RobotPose pose_;
73 RobotVelocity velocity_;
74};
75
76inline CartesianState operator*(const Affine &transform, const CartesianState &cartesian_state) {
77 return cartesian_state.transformWith(transform);
78}
79
80inline std::ostream &operator<<(std::ostream &os, const CartesianState &cartesian_state) {
81 os << "CartesianState(pose=" << cartesian_state.pose_ << ", velocity=" << cartesian_state.velocity_ << ")";
82 return os;
83}
84
85} // namespace franky
Definition cartesian_state.hpp:17
friend std::ostream & operator<<(std::ostream &os, const CartesianState &cartesian_state)
Definition cartesian_state.hpp:80
CartesianState(const RobotPose &pose, const RobotVelocity &velocity)
Definition cartesian_state.hpp:29
RobotPose pose() const
Definition cartesian_state.hpp:62
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:54
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: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
Affine end_effector_pose() const
Get the end effector pose.
Definition robot_pose.hpp:121
Cartesian velocity of a robot.
Definition robot_velocity.hpp:20
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:105
Definition dynamics_limit.cpp:8
std::ostream & operator<<(std::ostream &os, const DynamicsLimit< Vector7d > &limit)
Definition dynamics_limit.cpp:47
CartesianState operator*(const Affine &transform, const CartesianState &cartesian_state)
Definition cartesian_state.hpp:76
Eigen::Affine3d Affine
Definition types.hpp:15