5#include "fsb_configuration.h"
7#include "fsb_jacobian.h"
63 const Transform& pose,
const Jacobian& jacobian,
size_t columns =
MaxSize::kDofs);
74 const Transform& pose,
const Jacobian& jacobian,
size_t columns =
MaxSize::kDofs);
MotionVector spatial_body_to_space(const Transform &pose, const MotionVector &velocity_body)
Convert spatial velocity from space frame to body-fixed frame.
Definition fsb_spatial.cpp:38
Jacobian spatial_jacobian_body_to_space(const Transform &pose, const Jacobian &jacobian, size_t columns=MaxSize::kDofs)
Convert from jacobian in body frame to space frame.
Definition fsb_spatial.cpp:49
Transform transform_inverse_to_spatial(const Transform &transf)
Convert inverse of a coordinate transform to spatial transform.
Definition fsb_spatial.cpp:23
Transform transform_to_spatial(const Transform &transf)
Convert coordinate transform to spatial transform.
Definition fsb_spatial.cpp:15
MotionVector spatial_space_to_body(const Transform &pose, const MotionVector &velocity_space)
Convert spatial velocity from body frame to space frame.
Definition fsb_spatial.cpp:28
Jacobian spatial_jacobian_space_to_body(const Transform &pose, const Jacobian &jacobian, size_t columns=MaxSize::kDofs)
Convert from jacobian in space frame to body-fixed frame.
Definition fsb_spatial.cpp:77
static constexpr size_t kDofs
Maximum number of degrees of freedom.
Definition fsb_configuration.h:49