Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add visualizers (Robot Visualizer) and sensors libraries (IMUsensor) #41

Merged
merged 6 commits into from
May 2, 2021
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions app/robots/iCubGenova04/configRobot.m
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@

% Robot frames list
Frames.BASE = 'root_link';
Frames.IMU = 'imu_frame';
Frames.COM = 'com';
Frames.LEFT_FOOT = 'l_sole';
Frames.RIGHT_FOOT = 'r_sole';
Expand Down
74 changes: 74 additions & 0 deletions lib/+mwbs/+RobotSensors/+IMUsensor/IMUsensorProc.m
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
classdef IMUsensorProc < matlab.System
% IMUsensorProc This block computes the typical outputs of an IMU from the base pose and joints kinematics.
%
% Assuming DoFs is the number of internal degrees of freedom of the robot:
%
% Input:
% - w_H_b: Base pose, 4x4 matrix representing the homogenous transformation between the the
% base frame and the world frame.
% - nu: Base and joints velocities: Vector of size 6 representing the linear and angular
% velocity of the base frame, concatenated with a vector of size DoFs, representing the
% velocity of the joints.
% - nuDot: Base and joints accelerations: Vector of size 6 representing the linear and angular
% acceleration of the base frame, concatenated with a vector of size DoFs, representing the
% acceleration of the joints.
% - Jimu: Jacobian of the IMU frame.
% - JimuDotNu: Bias linear acceleration of the IMU frame with respect to the inertial (world)
% frame.
%
% Output:
% The sensor frame orientation, linear acceleration and angular velocity w.r.t. the inertial
% (world) frame. Linear acceleration and angular velocity are expressed in the world frame.
% - w_rollPitchYaw: roll, pitch, yaw Euler angles in rad.
% - w_linAcc: Proper linear acceleration in m/s^2.
% - w_omega: Angular velocity in rad/s.
% - imuOut: A [12x1] 1-D vector concatenating the previous three outputs and a placeholder for
% other measurements (e.g. magnetometer).
% [roll,pitch,yaw,accx,accy,accz,omegax,omegay,omegaz,0,0,0]'.
%
% Parameters:
% - Frame name: the name of the IMU frame. It should be specified in the URDF model.

% Public, tunable properties
properties

end

properties(DiscreteState)

end

% Pre-computed constants
properties(Access = private)

end

methods(Access = protected)
function setupImpl(obj)
% Perform one-time calculations, such as computing constants
end

function [imuOut,w_omega,w_linAcc,w_rollPitchYaw] = stepImpl(obj,Jimu,JimuDotNu,w_H_imu,nu,nudot)
% Implement algorithm. Calculate y as a function of inputs and discrete states.

% Gyroscope measurements
w_imuVel = Jimu*nu;
w_omega = w_imuVel(4:6);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is missing a rotation ${}^S R_A$, where $S$ is sensor frame and $A$ is the world/absolute frame. See equation 4.3 in https://traversaro.github.io/traversaro-phd-thesis/traversaro-phd-thesis.pdf .

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yes Silvio, you're right. I was going to fix this later on after finishing robotology/whole-body-controllers#122, and after checking those sections in your thesis about the sensor acceleration, just to be sure I wouldn't miss anything. That's why I specified in the issue and block documentation that the quantities where expressed in the world frame. But you're right, better do be accurate right away.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If you like to merge as it is for me it is ok, probably better to open an issue to eventually fix it, thanks1

Copy link
Collaborator Author

@nunoguedelha nunoguedelha Apr 30, 2021

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'll push here. Just quick question @traversaro . The WBT Jacobian block output is actually the jacobian expressed in a mixed frame right? B[A], i.e. the frame with origin of B and orientation of A, where B is the specified body frame and A the inertial frame. Such that J*nu gives:
$$
\begin{equation}
{}^{F _i[A]}\mathrm{v} _{A,F _i} = {}^{F _i[A]}R _{F _i} J _i \nu
\end{equation}
$$

Where $A$ is the inertial frame and $J_i$ is the Jacobian of body frame $F_i$ expressed in body coordinates as described in Featherstone RBDA textbook.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It should be the case, as in KinDynComputations.cpp, m_frameVelRepr is set to MIXED_REPRESENTATION.

Running the following in MATLAB command line getFrameVelocityRepresentation():

>> kinDyn = iDynTree.KinDynComputations()
>> kinDyn.getFrameVelocityRepresentation
ans =
  int64
   2

returns the default value: 2 => MIXED_REPRESENTATION. We get the same value while running RobotVisualizer.prepareRobot() which loads the robot model and prepares the robot visualization through the iDynTree bindings. Assuming that the Frame Velocity Representation is not explicitely changed later on through KinDynComputations::setFrameVelocityRepresentation method, we can assume that the Jacobian WBT block uses that type of representation. I've opened an issue to cross check that: #42 .

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'll push here. Just quick question @traversaro . The WBT Jacobian block output is actually the jacobian expressed in a mixed frame right? B[A], i.e. the frame with origin of B and orientation of A, where B is the specified body frame and A the inertial frame. Such that J*nu gives:
$$
\begin{equation}
{}^{F _i[A]}\mathrm{v} _{A,F _i} = {}^{F _i[A]}R _{F _i} J _i \nu
\end{equation}
$$

Where $A$ is the inertial frame and $J_i$ is the Jacobian of body frame $F_i$ expressed in body coordinates as described in Featherstone RBDA textbook.

In this formula, what is ${}^{F _i[A]}R _{F _i}$ ? Anyway, for iDynTree convention that formula is incomplete because if you pass from the mixed jacobian to the body-fixed jacobian, also the convention used by floating base velocity in the $\nu$ vector changes, so you need to also account for that. See equation 3.70 of https://traversaro.github.io/traversaro-phd-thesis/traversaro-phd-thesis.pdf for the correct formula.

In any case, yes all WB-Toolbox bocks use MIXED_REPRESENTATION and i do not think there is any way to change it, so it is safe to assume that the jacobian is the mixed one according to iDynTree convention.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

sorry, I meant actually ${}^{F _i[A]}X _{F _i}$ instead of $R$. And the Jacobian was already left trivialized. Nevertheless I shouldn't mention Featherstone as he addresses the fixed base casein the sections I was thinking about. Anyway, it's much clearer now for me, after reading again the respective section in your thesis. Thanks!


% Accelerometer measurements
w_imuAcc = Jimu*nudot + JimuDotNu;
w_linAcc = w_imuAcc(1:3);
nunoguedelha marked this conversation as resolved.
Show resolved Hide resolved

% Euler angles estimation
R = mwbs.State.H2Rp(w_H_imu);
w_rollPitchYaw = wbc.rollPitchYawFromRotation(R);

% composite sensor output
imuOut = [w_rollPitchYaw; w_linAcc; w_omega; zeros(3,1)];
end

function resetImpl(~)
% Initialize / reset discrete-state properties
end
end
end
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
classdef Visualizer < matlab.System
% Visualizer matlab.System handling the robot visualization.
% go in app/robots/iCub*/initVisualizer.m to change the setup config
classdef RobotVisualizer < matlab.System
% RobotVisualizer matlab.System handling the robot visualization.
% go in app/robots/iCub*/initRobotVisualizer.m to change the setup config

properties (Nontunable)
config
Expand Down
3 changes: 3 additions & 0 deletions lib/+mwbs/+Visualizers/+robotVisualizer/initRobotVisualizer.m
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
%% configuration for the matlab iDyntree visualizer

confVisualizer.modelPath = mwbs.getModelPathFromFileNameAndYarpFinder(confVisualizer.fileName);
Binary file added lib/mwbs_lib.slx
Binary file not shown.
Binary file added lib/mwbs_robotSensors_lib.slx
Binary file not shown.
Binary file added lib/mwbs_visualizers_lib.slx
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,9 @@
% in the Library Browser
% and be cached in the browser repository

Browser.Library = 'robotDynamicsWithContacts_lib'; % name of the library
Browser.Library = 'mwbs_lib'; % name of the library

Browser.Name = 'RobotDynamicsWithContacts'; % library name that appears in the Library Browser
Browser.Name = 'Matlab Whole-body Simulator'; % library name that appears in the Library Browser

Browser.IsFlat = 0;

Expand Down
4 changes: 2 additions & 2 deletions src/robotVisualizer/initVisualizer.m → src/initVisualizer.m
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
%% configuration for the matlab iDyntree visualizer

confVisualizer.fileName = robot_config.fileName;
confVisualizer.modelPath = mwbs.getModelPathFromFileNameAndYarpFinder(confVisualizer.fileName);
confVisualizer.meshFilePrefix = robot_config.meshFilePrefix;
confVisualizer.jointOrder = robot_config.jointOrder;
confVisualizer.robotFrames = robot_config.robotFrames;
% initial infos specified in configRobot

% initial joints configuration specified in configRobot
confVisualizer.joints_positions = robot_config.initialConditions.s;
confVisualizer.world_H_base = robot_config.initialConditions.w_H_b;

Expand Down
Loading