@@ -14,7 +14,11 @@ class RobotPose {
14
14
15
15
RobotPose (const RobotPose &robot_pose);
16
16
17
+ // Suppress implicit conversion warning
18
+ #pragma clang diagnostic push
19
+ #pragma clang diagnostic ignored "-Wimplicit-conversion"
17
20
RobotPose (Affine end_effector_pose, std::optional<double > elbow_position = std::nullopt);
21
+ #pragma clang diagnostic pop
18
22
19
23
explicit RobotPose (const Vector7d &vector_repr, bool ignore_elbow = false );
20
24
@@ -27,15 +31,19 @@ class RobotPose {
27
31
[[nodiscard]] franka::CartesianPose as_franka_pose () const ;
28
32
29
33
[[nodiscard]] inline RobotPose left_transform (const Affine &transform) const {
30
- return RobotPose ( transform * end_effector_pose_, elbow_position_) ;
34
+ return { transform * end_effector_pose_, elbow_position_} ;
31
35
}
32
36
33
37
[[nodiscard]] inline RobotPose right_transform (const Affine &transform) const {
34
- return RobotPose (end_effector_pose_ * transform, elbow_position_);
38
+ return {end_effector_pose_ * transform, elbow_position_};
39
+ }
40
+
41
+ [[nodiscard]] inline RobotPose changeEndEffectorFrame (const Affine &transform) const {
42
+ return {end_effector_pose_ * transform.inverse (), elbow_position_};
35
43
}
36
44
37
45
[[nodiscard]] inline RobotPose with_elbow_position (const std::optional<double > elbow_position) const {
38
- return RobotPose ( end_effector_pose_, elbow_position) ;
46
+ return { end_effector_pose_, elbow_position} ;
39
47
}
40
48
41
49
[[nodiscard]] inline Affine end_effector_pose () const {
0 commit comments