Skip to content

Commit 1bc2d2d

Browse files
author
Tim Schneider
committed
Got rid of Vector type definition
1 parent e86fe4d commit 1bc2d2d

File tree

5 files changed

+21
-23
lines changed

5 files changed

+21
-23
lines changed

include/franky/path/time_parametrization.hpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -31,12 +31,12 @@ class TimeParametrization {
3131
// For blend segments: Constant path velocity ds
3232
// Check continuous, and go back to zero velocity otherwise
3333

34-
Vector<state_dimensions> max_velocity_v = Eigen::Map<const Vector<state_dimensions>>(
35-
max_velocity.data(), max_velocity.size());
36-
Vector<state_dimensions> max_accleration_v = Eigen::Map<const Vector<state_dimensions>>(
37-
max_acceleration.data(), max_acceleration.size());
38-
Vector<state_dimensions> max_jerk_v = Eigen::Map<const Vector<state_dimensions>>(
39-
max_jerk.data(), max_jerk.size());
34+
Eigen::Vector<double, state_dimensions> max_velocity_v = \
35+
Eigen::Map<const Eigen::Vector<double, state_dimensions>>(max_velocity.data(), max_velocity.size());
36+
Eigen::Vector<double, state_dimensions> max_accleration_v = \
37+
Eigen::Map<const Eigen::Vector<double, state_dimensions>>(max_acceleration.data(), max_acceleration.size());
38+
Eigen::Vector<double, state_dimensions> max_jerk_v = \
39+
Eigen::Map<const Eigen::Vector<double, state_dimensions>>(max_jerk.data(), max_jerk.size());
4040

4141
std::vector<std::tuple<double, double, double>> max_path_dynamics;
4242
for (auto segment : path.segments()) {

include/franky/robot.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ struct InvalidMotionTypeException : public std::runtime_error {
3030
class Robot : public franka::Robot {
3131
public:
3232
template<size_t dims>
33-
using ScalarOrArray = std::variant<double, std::array<double, dims>, Vector<dims>>;
33+
using ScalarOrArray = std::variant<double, std::array<double, dims>, Eigen::Vector<double, dims>>;
3434

3535
struct Params {
3636
RelativeDynamicsFactor relative_dynamics_factor{1.0};
@@ -258,8 +258,8 @@ class Robot : public franka::Robot {
258258
std::array<double, dims> expand(const ScalarOrArray<dims> &input) {
259259
if (std::holds_alternative<std::array<double, dims>>(input)) {
260260
return std::get<std::array<double, dims>>(input);
261-
} else if (std::holds_alternative<Vector<dims>>(input)) {
262-
return toStd<dims>(std::get<Vector<dims>>(input));
261+
} else if (std::holds_alternative<Eigen::Vector<double, dims>>(input)) {
262+
return toStd<dims>(std::get<Eigen::Vector<double, dims>>(input));
263263
} else {
264264
std::array<double, dims> output;
265265
std::fill(output.begin(), output.end(), std::get<double>(input));

include/franky/types.hpp

+2-5
Original file line numberDiff line numberDiff line change
@@ -5,11 +5,8 @@
55

66
namespace franky {
77

8-
template<size_t dims>
9-
using Vector = Eigen::Matrix<double, dims, 1>;
10-
11-
using Vector6d = Vector<6>;
12-
using Vector7d = Vector<7>;
8+
using Vector6d = Eigen::Vector<double, 6>;
9+
using Vector7d = Eigen::Vector<double, 7>;
1310

1411
using Euler = Eigen::EulerAngles<double, Eigen::EulerSystemXYZ>;
1512

python/python.cpp

+6-5
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ using namespace franky;
3333
SequentialExecutor callback_executor;
3434

3535
template<int dims>
36-
std::string vecToStr(const Vector<dims> &vec) {
36+
std::string vecToStr(const Eigen::Vector<double, dims> &vec) {
3737
std::stringstream ss;
3838
ss << "[";
3939
for (size_t i = 0; i < dims; i++) {
@@ -419,10 +419,10 @@ PYBIND11_MODULE(_franky, m) {
419419
py::class_<Affine>(m, "Affine")
420420
.def(py::init<const Eigen::Matrix<double, 4, 4> &>(),
421421
"transformation_matrix"_a = Eigen::Matrix<double, 4, 4>::Identity())
422-
.def(py::init<>([](const Vector<3> &translation, const Vector<4> &quaternion) {
422+
.def(py::init<>([](const Eigen::Vector3d &translation, const Eigen::Vector4d &quaternion) {
423423
return Affine().fromPositionOrientationScale(
424-
translation, Eigen::Quaterniond(quaternion), Vector<3>::Ones());
425-
}), "translation"_a = Vector<3>{0, 0, 0}, "quaternion"_a = Vector<4>{0, 0, 0, 1})
424+
translation, Eigen::Quaterniond(quaternion), Eigen::Vector3d::Ones());
425+
}), "translation"_a = Eigen::Vector3d{0, 0, 0}, "quaternion"_a = Eigen::Vector4d{0, 0, 0, 1})
426426
.def(py::init<const Affine &>()) // Copy constructor
427427
.def(py::self * py::self)
428428
.def_property_readonly("inverse", [](const Affine &affine) { return affine.inverse(); })
@@ -444,7 +444,8 @@ PYBIND11_MODULE(_franky, m) {
444444
if (t.size() != 2)
445445
throw std::runtime_error("Invalid state!");
446446
return Affine().fromPositionOrientationScale(
447-
t[0].cast<Vector<3>>(), Eigen::Quaterniond(t[1].cast<Vector<4>>()), Vector<3>::Ones());
447+
t[0].cast<Eigen::Vector3d>(),
448+
Eigen::Quaterniond(t[1].cast<Eigen::Vector4d>()), Eigen::Vector3d::Ones());
448449
}
449450
));
450451

src/motion/cartesian_waypoint_motion.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -22,10 +22,10 @@ void CartesianWaypointMotion::initWaypointMotion(
2222
RobotPose robot_pose(previous_command.value_or(franka::CartesianPose{robot_state.O_T_EE_c, robot_state.elbow_c}));
2323
ref_frame_ = Affine::Identity();
2424

25-
auto initial_velocity = Vector<6>::Map(robot_state.O_dP_EE_c.data());
25+
auto initial_velocity = Vector6d::Map(robot_state.O_dP_EE_c.data());
2626
Vector7d initial_velocity_with_elbow = (Vector7d() << initial_velocity, robot_state.delbow_c[0]).finished();
2727

28-
auto initial_acceleration = Vector<6>::Map(robot_state.O_ddP_EE_c.data());
28+
auto initial_acceleration = Vector6d::Map(robot_state.O_ddP_EE_c.data());
2929
Vector7d initial_acceleration_with_elbow = (Vector7d() << initial_acceleration, robot_state.ddelbow_c[0]).finished();
3030

3131
target_robot_pose_ = robot_pose;
@@ -54,11 +54,11 @@ void CartesianWaypointMotion::setNewWaypoint(
5454
ref_frame_ = ref_frame_ * new_ref_to_old_ref;
5555
auto rot = new_ref_to_old_ref.inverse().rotation();
5656

57-
Vector<7> current_velocity = toEigen<7>(input_parameter.current_velocity);
57+
Vector7d current_velocity = toEigen<7>(input_parameter.current_velocity);
5858
auto linear_vel_ref_frame = rot * current_velocity.head<3>();
5959
auto angular_vel_ref_frame = rot * current_velocity.segment<3>(3);
6060

61-
Vector<7> current_acc = toEigen<7>(input_parameter.current_acceleration);
61+
Vector7d current_acc = toEigen<7>(input_parameter.current_acceleration);
6262
auto linear_acc_ref_frame = rot * current_acc.head<3>();
6363
auto angular_acc_ref_frame = rot * current_acc.segment<3>(3);
6464

0 commit comments

Comments
 (0)