-
Notifications
You must be signed in to change notification settings - Fork 68
/
getRobotState.m
75 lines (59 loc) · 2.89 KB
/
getRobotState.m
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
function [basePose,jointPos,baseVel,jointVel] = getRobotState(KinDynModel)
% GETROBOTSTATE gets the floating base system state from the reduced model.
%
% This matlab function wraps a functionality of the iDyntree library.
% For further info see also: https://github.com/robotology/idyntree
%
% FORMAT: [basePose,jointPos,baseVel,jointVel] = getRobotState(KinDynModel)
%
% INPUTS: - KinDynModel: a structure containing the loaded model and additional info.
%
% OUTPUTS: - basePose: [4 x 4] from base frame to world frame transform;
% - jointPos: [ndof x 1] vector of joint positions;
% - baseVel: [6 x 1] vector of base velocity;
% - jointVel: [ndof x 1] vector of joint velocities.
%
% Author : Gabriele Nava ([email protected])
%
% SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT)
% SPDX-License-Identifier: BSD-3-Clause
%% ------------Initialization----------------
% get the floating base state
KinDynModel.kinDynComp.getRobotState(KinDynModel.kinematics.basePose_iDyntree,KinDynModel.kinematics.jointPos_iDyntree, ...
KinDynModel.kinematics.baseVel_iDyntree,KinDynModel.kinematics.jointVel_iDyntree, ...
KinDynModel.kinematics.gravityVec_iDyntree);
% get the base position and orientation
baseRotation_iDyntree = KinDynModel.kinematics.basePose_iDyntree.getRotation;
baseOrigin_iDyntree = KinDynModel.kinematics.basePose_iDyntree.getPosition;
% covert to Matlab format
baseRotation = baseRotation_iDyntree.toMatlab;
baseOrigin = baseOrigin_iDyntree.toMatlab;
basePose = [baseRotation, baseOrigin;
0, 0, 0, 1];
jointPos = KinDynModel.kinematics.jointPos_iDyntree.toMatlab;
baseVel = KinDynModel.kinematics.baseVel_iDyntree.toMatlab;
jointVel = KinDynModel.kinematics.jointVel_iDyntree.toMatlab;
% Debug output
if KinDynModel.DEBUG
disp('[getRobotState]: debugging outputs...')
% baseRotation = basePose(1:3,1:3) must be a valid rotation matrix
if det(basePose(1:3,1:3)) < 0.9 || det(basePose(1:3,1:3)) > 1.1
error('[getRobotState]: baseRotation is not a valid rotation matrix.')
end
IdentityMatr = basePose(1:3,1:3)*basePose(1:3,1:3)';
for kk = 1:size(IdentityMatr, 1)
for jj = 1:size(IdentityMatr, 1)
if jj == kk
if abs(IdentityMatr(kk,jj)) < 0.9 || abs(IdentityMatr(kk,jj)) > 1.1
error('[getRobotState]: baseRotation is not a valid rotation matrix.')
end
else
if abs(IdentityMatr(kk,jj)) > 0.01
error('[getRobotState]: baseRotation is not a valid rotation matrix.')
end
end
end
end
disp('[getRobotState]: done.')
end
end