FancySafeBot 0.0.1
A safe robotics library
Loading...
Searching...
No Matches
fsb_jacobian.h
1
2#ifndef FSB_JACOBIAN_H
3#define FSB_JACOBIAN_H
4
5#include <array>
6#include <cstddef>
7#include <cstdint>
8#include "fsb_body.h"
9#include "fsb_body_tree.h"
10#include "fsb_configuration.h"
11#include "fsb_joint.h"
12#include "fsb_motion.h"
13#include "fsb_types.h"
14
15namespace fsb
16{
17
28{
32 std::array<real_t, 6U * MaxSize::dofs> j;
33};
34
39{
43 std::array<real_t, MaxSize::dofs * MaxSize::dofs> j;
44};
45
49struct Hessian
50{
54 std::array<Jacobian, MaxSize::dofs> h;
55};
56
60enum class JacobianError : uint8_t
61{
65 SUCCESS,
70};
71
81inline size_t jacobian_index(const size_t row, const size_t col)
82{
83 return 6U * col + row;
84}
85
96inline size_t joint_matrix_index(const size_t row, const size_t col, const size_t dofs)
97{
98 return dofs * col + row;
99}
100
109MotionVector jacobian_multiply(
110 const Jacobian& jacobian, const JointSpace& joint_motion, size_t dofs = MaxSize::dofs);
111
121 const Jacobian& jacobian, const MotionVector& cartesian_motion, size_t dofs = MaxSize::dofs);
122
133JointMatrix jacobian_transpose_multiply_jacobian(const Jacobian& jacobian, const MotionVector& cartesian_weights, size_t dofs = MaxSize::dofs);
134
143Jacobian jacobian_derivative(
144 const Hessian& hessian, const JointSpace& joint_velocity, size_t dofs = MaxSize::dofs);
145
159 size_t body_index, const BodyTree& body_tree, const BodyCartesianPva& cartesian_pva,
160 Jacobian& jacobian);
161
166} // namespace fsb
167
168#endif // FSB_JACOBIAN_H
size_t joint_matrix_index(const size_t row, const size_t col, const size_t dofs)
Helper function for indexing joint matrix.
Definition fsb_jacobian.h:96
JointSpace jacobian_transpose_multiply(const Jacobian &jacobian, const MotionVector &cartesian_motion, size_t dofs=MaxSize::dofs)
Jacobian transpose multiply cartesian motion.
Definition fsb_jacobian.cpp:277
JointMatrix jacobian_transpose_multiply_jacobian(const Jacobian &jacobian, const MotionVector &cartesian_weights, size_t dofs=MaxSize::dofs)
Jacobian transpose multiply jacobian.
Definition fsb_jacobian.cpp:298
MotionVector jacobian_multiply(const Jacobian &jacobian, const JointSpace &joint_motion, size_t dofs=MaxSize::dofs)
Jacobian multiply joint velocity.
Definition fsb_jacobian.cpp:257
JacobianError calculate_jacobian(size_t body_index, const BodyTree &body_tree, const BodyCartesianPva &cartesian_pva, Jacobian &jacobian)
Determine Jacobian matrix for a single body in tree.
Definition fsb_jacobian.cpp:217
size_t jacobian_index(const size_t row, const size_t col)
Helper function for indexing jacobian matrix.
Definition fsb_jacobian.h:81
JacobianError
Error values for Jacobian calculations.
Definition fsb_jacobian.h:61
Jacobian jacobian_derivative(const Hessian &hessian, const JointSpace &joint_velocity, size_t dofs=MaxSize::dofs)
Compute derivative of Jacobian matrix.
Definition fsb_jacobian.cpp:331
@ BODY_NOT_IN_TREE
Index does not point to an existing body in tree.
Hessian tensor.
Definition fsb_jacobian.h:50
std::array< Jacobian, MaxSize::dofs > h
Hessian tensor data "pages".
Definition fsb_jacobian.h:54
Jacobian matrix.
Definition fsb_jacobian.h:28
std::array< real_t, 6U *MaxSize::dofs > j
Jacobian matrix data array.
Definition fsb_jacobian.h:32
Square matrix of size nxn for n joints.
Definition fsb_jacobian.h:39
std::array< real_t, MaxSize::dofs *MaxSize::dofs > j
Square matrix data array.
Definition fsb_jacobian.h:43
static constexpr size_t dofs
Maximum number of degrees of freedom.
Definition fsb_configuration.h:49