Franky 0.12.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
util.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <franka/duration.h>
4
5#include <Eigen/Core>
6#include <array>
7
8namespace franky {
9
10template<typename T, size_t dims>
11std::array<T, dims> toStd(const Eigen::Matrix<T, dims, 1> &vector) {
12 std::array<T, dims> result;
13 Eigen::Matrix<T, dims, 1>::Map(result.data()) = vector;
14 return result;
15}
16
17template<size_t dims>
18std::array<double, dims> toStdD(const Eigen::Matrix<double, dims, 1> &vector) {
20}
21
22template<typename T, size_t dims>
23Eigen::Matrix<T, dims, 1> toEigen(const std::array<T, dims> &vector) {
24 return Eigen::Matrix<T, dims, 1>::Map(vector.data());
25}
26
27template<size_t dims>
28Eigen::Matrix<double, dims, 1> toEigenD(const std::array<double, dims> &vector) {
30}
31
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;
36 return result;
37}
38
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());
42}
43
44inline Affine stdToAffine(const std::array<double, 16> &array) {
46 result.matrix() = toEigenMatD<4, 4>(array);
47 return result;
48}
49
50template<size_t dims>
51Eigen::Vector<double, dims> ensureEigen(const Array<dims> &input) {
52 if (std::holds_alternative<Eigen::Vector<double, dims>>(input))
53 return std::get<Eigen::Vector<double, dims>>(input);
54 return toEigenD<dims>(std::get<std::array<double, dims >>(input));
55}
56
57template<size_t dims>
58std::array<double, dims> ensureStd(const Array<dims> &input) {
59 if (std::holds_alternative<std::array<double, dims >>(input))
60 return std::get<std::array<double, dims >>(input);
61 return toStdD<dims>(std::get<Eigen::Vector<double, dims >>(input));
62}
63
64template<size_t dims>
65std::array<double, dims> expand(const ScalarOrArray<dims> &input) {
66 if (std::holds_alternative<Array<dims>>(input)) {
67 return ensureStd<dims>(std::get<Array<dims>>(input));
68 }
69 std::array<double, dims> output;
70 std::fill(output.begin(), output.end(), std::get<double>(input));
71 return output;
72}
73
74template<int dims>
75std::ostream &operator<<(std::ostream &os, const Eigen::Vector<double, dims> &vec) {
76 os << "[";
77 for (size_t i = 0; i < dims; i++) {
78 os << vec[i];
79 if (i != dims - 1)
80 os << " ";
81 }
82 os << "]";
83 return os;
84}
85
86inline std::ostream &operator<<(std::ostream &os, const Affine &affine) {
87 os << "Affine(t=" << affine.translation().eval() << ", q=" << Eigen::Quaterniond(affine.rotation()).coeffs()
88 << ")";
89 return os;
90}
91
92inline std::ostream &operator<<(std::ostream &os, const franka::Duration &duration) {
93 os << "Duration(" << duration.toMSec() << ")";
94 return os;
95}
96
97} // namespace franky
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