3#include <franka/duration.h>
10template<
typename T,
size_t dims>
11std::array<T, dims>
toStd(
const Eigen::Matrix<T, dims, 1> &
vector) {
12 std::array<T, dims>
result;
18std::array<double, dims>
toStdD(
const Eigen::Matrix<double, dims, 1> &
vector) {
22template<
typename T,
size_t dims>
24 return Eigen::Matrix<T, dims, 1>::Map(
vector.data());
28Eigen::Matrix<double, dims, 1>
toEigenD(
const std::array<double, dims> &
vector) {
32template<
size_t rows,
size_t cols>
33std::array<double, rows * cols>
toStdDMatD(
const Eigen::Matrix<double, rows, cols, Eigen::ColMajor> &
matrix) {
34 std::array<double, rows * cols>
result;
35 Eigen::Map<Eigen::Matrix<double, rows, cols, Eigen::ColMajor>>(
result.data()) =
matrix;
39template <
size_t rows,
size_t cols>
40Eigen::Matrix<double, rows, cols, Eigen::ColMajor>
toEigenMatD(
const std::array<double, rows * cols> &
array) {
41 return Eigen::Map<const Eigen::Matrix<double, rows, cols, Eigen::ColMajor>>(
array.data());
52 if (std::holds_alternative<Eigen::Vector<double, dims>>(
input))
53 return std::get<Eigen::Vector<double, dims>>(
input);
59 if (std::holds_alternative<std::array<double, dims >>(
input))
60 return std::get<std::array<double, dims >>(
input);
69 std::array<double, dims>
output;
75std::ostream &
operator<<(std::ostream &
os,
const Eigen::Vector<double, dims> &
vec) {
77 for (
size_t i = 0;
i <
dims;
i++) {
87 os <<
"Affine(t=" <<
affine.translation().eval() <<
", q=" << Eigen::Quaterniond(
affine.rotation()).coeffs()
Definition dynamics_limit.cpp:8
std::ostream & operator<<(std::ostream &os, const DynamicsLimit< Vector7d > &limit)
Definition dynamics_limit.cpp:47
std::array< double, dims > toStdD(const Eigen::Matrix< double, dims, 1 > &vector)
Definition util.hpp:18
Eigen::Matrix< T, dims, 1 > toEigen(const std::array< T, dims > &vector)
Definition util.hpp:23
std::array< double, rows *cols > toStdDMatD(const Eigen::Matrix< double, rows, cols, Eigen::ColMajor > &matrix)
Definition util.hpp:33
Eigen::Matrix< double, rows, cols, Eigen::ColMajor > toEigenMatD(const std::array< double, rows *cols > &array)
Definition util.hpp:40
Eigen::Vector< double, dims > ensureEigen(const Array< dims > &input)
Definition util.hpp:51
std::array< T, dims > toStd(const Eigen::Matrix< T, dims, 1 > &vector)
Definition util.hpp:11
std::array< double, dims > ensureStd(const Array< dims > &input)
Definition util.hpp:58
Affine stdToAffine(const std::array< double, 16 > &array)
Definition util.hpp:44
std::array< double, dims > expand(const ScalarOrArray< dims > &input)
Definition util.hpp:65
std::variant< double, Array< dims > > ScalarOrArray
Definition types.hpp:22
std::variant< std::array< double, dims >, Eigen::Vector< double, dims > > Array
Definition types.hpp:19
Eigen::Matrix< double, dims, 1 > toEigenD(const std::array< double, dims > &vector)
Definition util.hpp:28
Eigen::Affine3d Affine
Definition types.hpp:16