include
opw_kinematics
opw_kinematics.h
Go to the documentation of this file.
1
#ifndef OPW_KINEMATICS_H
2
#define OPW_KINEMATICS_H
3
4
#include <array>
// IWYU pragma: keep
5
#include <Eigen/Dense>
// IWYU pragma: keep
6
#include "
opw_kinematics/opw_parameters.h
"
// IWYU pragma: export
7
8
namespace
opw_kinematics
9
{
14
template
<
typename
T>
15
using
Transform
= Eigen::Transform<T, 3, Eigen::Isometry>;
16
21
template
<
typename
T>
22
using
Solutions
= std::array<std::array<T, 6>, 8>;
23
37
template
<
typename
T>
38
Solutions<T>
inverse
(
const
Parameters<T>
& params,
const
Transform<T>
& pose) noexcept;
39
47
template
<
typename
T>
48
Transform<T>
forward
(
const
Parameters<T>
& p,
const
std::array<T, 6>& qs) noexcept;
49
50
}
// end namespace opw_kinematics
51
52
#include "
opw_kinematics/opw_kinematics_impl.h
"
// IWYU pragma: export
53
54
#endif // OPW_KINEMATICS_H
opw_kinematics
Definition:
opw_io.h:7
opw_kinematics::Transform
Eigen::Transform< T, 3, Eigen::Isometry > Transform
Definition:
opw_kinematics.h:15
opw_kinematics::Solutions
std::array< std::array< T, 6 >, 8 > Solutions
Definition:
opw_kinematics.h:22
opw_kinematics::forward
Transform< T > forward(const Parameters< T > &p, const std::array< T, 6 > &qs) noexcept
Computes the tool pose of the robot described by when said robot has the joint positions given by qs,...
Definition:
opw_kinematics_impl.h:34
opw_kinematics::inverse
Solutions< T > inverse(const Parameters< T > ¶ms, const Transform< T > &pose) noexcept
Computes up to 8 kinematically unique joint solutions that put the tool flange of the robot described...
Definition:
opw_kinematics_impl.h:113
opw_kinematics::Parameters
Definition:
opw_parameters.h:10
opw_parameters.h
opw_kinematics_impl.h
opw_kinematics
Author(s): Jon Meyer
, Jeroen De Maeyer
autogenerated on Thu Jan 16 2025 03:40:37