Skip to content

Commit a9b5924

Browse files
Made RobotVelocity.elbow_velocity non-optional
1 parent 887dfd8 commit a9b5924

File tree

4 files changed

+28
-27
lines changed

4 files changed

+28
-27
lines changed

include/franky/robot.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,7 @@ class Robot : public franka::Robot {
133133
[[nodiscard]] inline CartesianState currentCartesianState() {
134134
auto s = state();
135135
return {{Affine(Eigen::Matrix4d::Map(s.O_T_EE.data())), s.elbow[0]},
136-
RobotVelocity(Vector6d::Map(s.O_dP_EE_c.data()), std::optional<double>(s.delbow_c[0]))};
136+
RobotVelocity(franka::CartesianVelocities(s.O_dP_EE_c, s.delbow_c))};
137137
}
138138

139139
[[nodiscard]] Vector7d currentJointPositions();

include/franky/robot_velocity.hpp

+10-8
Original file line numberDiff line numberDiff line change
@@ -11,13 +11,19 @@ namespace franky {
1111

1212
class RobotVelocity {
1313
public:
14+
RobotVelocity();
15+
1416
RobotVelocity(const RobotVelocity &robot_velocity);
1517

16-
RobotVelocity(Twist end_effector_twist, std::optional<double> elbow_velocity = std::nullopt);
18+
RobotVelocity(RobotVelocity &&robot_velocity) noexcept;
1719

18-
explicit RobotVelocity(const Vector7d &vector_repr, bool ignore_elbow = false);
20+
// Suppress implicit conversion warning
21+
#pragma clang diagnostic push
22+
#pragma clang diagnostic ignored "-Wimplicit-conversion"
23+
RobotVelocity(Twist end_effector_twist, double elbow_velocity = 0.0);
24+
#pragma clang diagnostic pop
1925

20-
explicit RobotVelocity(const Vector6d &vector_repr, std::optional<double> elbow_velocity = std::nullopt);
26+
explicit RobotVelocity(const Vector7d &vector_repr);
2127

2228
explicit RobotVelocity(franka::CartesianVelocities franka_velocity);
2329

@@ -42,10 +48,6 @@ class RobotVelocity {
4248
return {end_effector_twist_.propagateThroughLink(offset_world_frame), elbow_velocity_};
4349
}
4450

45-
[[nodiscard]] inline RobotVelocity with_elbow_velocity(const std::optional<double> elbow_velocity) const {
46-
return {end_effector_twist_, elbow_velocity};
47-
}
48-
4951
[[nodiscard]] inline Twist end_effector_twist() const {
5052
return end_effector_twist_;
5153
}
@@ -56,7 +58,7 @@ class RobotVelocity {
5658

5759
private:
5860
Twist end_effector_twist_;
59-
std::optional<double> elbow_velocity_;
61+
double elbow_velocity_ = 0.0;
6062
};
6163

6264
inline RobotVelocity operator*(const Affine &affine, const RobotVelocity &robot_velocity) {

python/python.cpp

+3-4
Original file line numberDiff line numberDiff line change
@@ -532,10 +532,9 @@ PYBIND11_MODULE(_franky, m) {
532532
py::implicitly_convertible<Affine, RobotPose>();
533533

534534
py::class_<RobotVelocity>(m, "RobotVelocity")
535-
.def(py::init<Twist, std::optional<double>>(), "end_effector_twist"_a, "elbow_velocity"_a = std::nullopt)
535+
.def(py::init<Twist, double>(), "end_effector_twist"_a, "elbow_velocity"_a = 0.0)
536536
.def(py::init<const RobotVelocity &>()) // Copy constructor
537537
.def("change_end_effector_frame", &RobotVelocity::changeEndEffectorFrame, "offset_world_frame"_a)
538-
.def("with_elbow_velocity", &RobotVelocity::with_elbow_velocity, "elbow_velocity"_a)
539538
.def_property_readonly("end_effector_twist", &RobotVelocity::end_effector_twist)
540539
.def_property_readonly("elbow_velocity", &RobotVelocity::elbow_velocity)
541540
.def("__rmul__",
@@ -550,9 +549,9 @@ PYBIND11_MODULE(_franky, m) {
550549
return py::make_tuple(robot_velocity.end_effector_twist(), robot_velocity.elbow_velocity());
551550
},
552551
[](const py::tuple &t) { // __setstate__
553-
if (t.size() != 3)
552+
if (t.size() != 2)
554553
throw std::runtime_error("Invalid state!");
555-
return RobotVelocity(t[0].cast<Twist>(), t[1].cast<std::optional<double>>());
554+
return RobotVelocity(t[0].cast<Twist>(), t[1].cast<double>());
556555
}
557556
));
558557

src/robot_velocity.cpp

+14-14
Original file line numberDiff line numberDiff line change
@@ -9,37 +9,37 @@
99

1010
namespace franky {
1111

12+
RobotVelocity::RobotVelocity() = default;
13+
1214
RobotVelocity::RobotVelocity(const RobotVelocity &) = default;
1315

14-
RobotVelocity::RobotVelocity(Twist end_effector_twist, std::optional<double> elbow_velocity)
16+
RobotVelocity::RobotVelocity(RobotVelocity &&) noexcept = default;
17+
18+
RobotVelocity::RobotVelocity(Twist end_effector_twist, double elbow_velocity)
1519
: end_effector_twist_(std::move(end_effector_twist)),
1620
elbow_velocity_(elbow_velocity) {}
1721

18-
RobotVelocity::RobotVelocity(const Vector7d &vector_repr, bool ignore_elbow)
19-
: RobotVelocity(
20-
vector_repr.head<6>(),
21-
ignore_elbow ? std::optional<double>(std::nullopt) : vector_repr[6]) {}
22-
23-
RobotVelocity::RobotVelocity(const Vector6d &vector_repr, std::optional<double> elbow_velocity)
24-
: end_effector_twist_(vector_repr), elbow_velocity_(elbow_velocity) {}
22+
RobotVelocity::RobotVelocity(const Vector7d &vector_repr)
23+
: RobotVelocity(Twist{vector_repr.head<6>()}, vector_repr[6]) {}
2524

2625
RobotVelocity::RobotVelocity(const franka::CartesianVelocities franka_velocity)
27-
: RobotVelocity(Vector6d::Map(franka_velocity.O_dP_EE.data()), std::optional<double>(franka_velocity.elbow[0])) {}
26+
: RobotVelocity(
27+
{
28+
Vector6d::Map(franka_velocity.O_dP_EE.data()).tail<3>(),
29+
Vector6d::Map(franka_velocity.O_dP_EE.data()).head<3>()
30+
}, franka_velocity.elbow[0]) {}
2831

2932
Vector7d RobotVelocity::vector_repr() const {
3033
Vector7d result;
31-
result << end_effector_twist_.vector_repr(), elbow_velocity_.value_or(0.0);
34+
result << end_effector_twist_.vector_repr(), elbow_velocity_;
3235
return result;
3336
}
3437

3538
franka::CartesianVelocities RobotVelocity::as_franka_velocity() const {
3639
std::array<double, 6> array;
3740
auto vec = vector_repr().head<6>();
3841
std::copy(vec.data(), vec.data() + array.size(), array.begin());
39-
if (elbow_velocity_.has_value()) {
40-
return franka::CartesianVelocities(array, {elbow_velocity_.value(), -1});
41-
}
42-
return {array};
42+
return franka::CartesianVelocities(array, {elbow_velocity_, -1});
4343
}
4444

4545
} // namespace franky

0 commit comments

Comments
 (0)