FancySafeBot 0.0.1
A safe robotics library
Loading...
Searching...
No Matches
fsb_kinematics.h
1
2#ifndef FSB_KINEMATICS_H
3#define FSB_KINEMATICS_H
4
5#include <cstdint>
6#include "fsb_body.h"
7#include "fsb_body_tree.h"
8#include "fsb_joint.h"
9#include "fsb_motion.h"
10
11namespace fsb
12{
13
24enum class ForwardKinematicsOption: uint8_t
25{
29 POSE = 0,
33 POSE_VELOCITY = 1,
39};
40
51 const BodyTree& body_tree, const JointPva& joint_pva, const CartesianPva& base_pva,
52 ForwardKinematicsOption opt, BodyCartesianPva& body_cartesian);
53
62JointSpacePosition joint_add_offset(
63 const BodyTree& body_tree, const JointSpacePosition& joint_position, const JointSpace& joint_offset);
64
73JointSpace joint_difference(
74 const BodyTree& body_tree, const JointSpacePosition& joint_position_a, const JointSpacePosition& joint_position_b);
75
84 const BodyTree& body_tree, const BodyCartesianPva& body_cartesian,
85 BodyCartesianPva& com_cartesian);
86
91} // namespace fsb
92
93#endif
JointSpace joint_difference(const BodyTree &body_tree, const JointSpacePosition &joint_position_a, const JointSpacePosition &joint_position_b)
Get difference between joint positions.
Definition fsb_kinematics.cpp:170
void body_com_kinematics(const BodyTree &body_tree, const BodyCartesianPva &body_cartesian, BodyCartesianPva &com_cartesian)
Compute motion of center of mass for all bodies in tree.
Definition fsb_kinematics.cpp:63
void forward_kinematics(const BodyTree &body_tree, const JointPva &joint_pva, const CartesianPva &base_pva, ForwardKinematicsOption opt, BodyCartesianPva &body_cartesian)
Compute forward kinematics for all bodies in tree.
Definition fsb_kinematics.cpp:38
JointSpacePosition joint_add_offset(const BodyTree &body_tree, const JointSpacePosition &joint_position, const JointSpace &joint_offset)
Add offset to joint position.
Definition fsb_kinematics.cpp:81
ForwardKinematicsOption
Forward kinematics options.
Definition fsb_kinematics.h:25
@ POSE_VELOCITY
Calculate Cartesian pose and velocity from joint position and velocity.
@ POSE
Calculate Cartesian pose from joint position.
@ POSE_VELOCITY_ACCELERATION
Calculate Cartesian pose, velocity and acceleration from joint position, velocity,...