Skip to content
Merged
3 changes: 1 addition & 2 deletions robot_modeling/DQ_FreeFlyingRobot.m
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
%
% See also DQ_MobileBase, DQ_DifferentialDriveRobot, DQ_HolonomicBase

% (C) Copyright 2011-2020 DQ Robotics Developers
% (C) Copyright 2011-2023 DQ Robotics Developers
%
% This file is part of DQ Robotics.
%
Expand Down Expand Up @@ -45,7 +45,6 @@
end

properties (Access = private)
dim_configuration_space;
shape_template;
handle;
end
Expand Down
10 changes: 8 additions & 2 deletions robot_modeling/DQ_Kinematics.m
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
% translation_jacobian - Compute the translation Jacobian.
% See also DQ_SerialManipulator, DQ_MobileBase, DQ_CooperativeDualTaskSpace.

% (C) Copyright 2011-2022 DQ Robotics Developers
% (C) Copyright 2011-2023 DQ Robotics Developers
%
% This file is part of DQ Robotics.
%
Expand All @@ -56,7 +56,11 @@
% DQ Robotics website: dqrobotics.github.io
%
% Contributors to this file:
% Bruno Vihena Adorno - adorno@ieee.org
% 1. Bruno Vihena Adorno (adorno@ieee.org)
% Responsible for the original implementation.
%
% 2. Juan Jose Quiroz Omana (juanjqo@g.ecc.u-tokyo.ac.jp)
% - Added the property dim_configuration_space.

classdef DQ_Kinematics < handle
% DQ_Kinematics inherits the HANDLE superclass to avoid unnecessary copies
Expand All @@ -74,6 +78,8 @@
base_frame;
% Robot configuration vector
q;
% Dimension of the configuration space
dim_configuration_space;
end

methods
Expand Down
5 changes: 2 additions & 3 deletions robot_modeling/DQ_MobileBase.m
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
%
% See also DQ_Kinematics, DQ_HolonomicBase.

% (C) Copyright 2011-2019 DQ Robotics Developers
% (C) Copyright 2011-2023 DQ Robotics Developers
%
% This file is part of DQ Robotics.
%
Expand All @@ -38,7 +38,7 @@
% DQ Robotics website: dqrobotics.github.io
%
% Contributors to this file:
% Bruno Vihena Adorno - adorno@ufmg.br
% Bruno Vihena Adorno - adorno@ieee.org

classdef (Abstract) DQ_MobileBase < DQ_Kinematics
properties
Expand All @@ -47,7 +47,6 @@

properties (Access = protected)
handle;
dim_configuration_space;
frame_displacement;
end

Expand Down
28 changes: 16 additions & 12 deletions robot_modeling/DQ_SerialManipulator.m
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,12 @@
% DQ Robotics website: dqrobotics.github.io
%
% Contributors to this file:
% Bruno Vihena Adorno - adorno@ieee.org
% 1. Bruno Vihena Adorno - adorno@ieee.org
% Responsible for the original implementation.
%
% 2. Juan Jose Quiroz Omana (juanjqo@g.ecc.u-tokyo.ac.jp)
% - Removed the property n_links. The dimension of the configuration
% space is now stored in DQ_Kinematics.dim_configuration_space.

classdef (Abstract) DQ_SerialManipulator < DQ_Kinematics
properties
Expand All @@ -50,7 +55,6 @@
% Handle used to access the robot's graphics information. It's used
% mainly in the plot function.
handle
n_links;
joint_types;
end

Expand Down Expand Up @@ -133,7 +137,7 @@ function check_joint_types(obj)
end

function ret = get_dim_configuration_space(obj)
ret = obj.n_links;
ret = obj.dim_configuration_space;
end

function set_effector(obj,effector)
Expand Down Expand Up @@ -214,7 +218,7 @@ function set_joint_type(obj, joint_type, ith_joint)
if nargin == 3
n = to_ith_link;
else
n = obj.n_links;
n = obj.get_dim_configuration_space();
end

x = DQ(1);
Expand All @@ -239,7 +243,7 @@ function set_joint_type(obj, joint_type, ith_joint)
% internally in DQ_kinematics

if nargin < 3
to_ith_link = obj.n_links;
to_ith_link = obj.get_dim_configuration_space();
end
x_effector = obj.raw_fkm(q,to_ith_link);

Expand Down Expand Up @@ -272,7 +276,7 @@ function set_joint_type(obj, joint_type, ith_joint)
J = obj.raw_pose_jacobian(q,to_ith_link);
vec_x_effector_dot = J*q_dot(1:to_ith_link);
else
n = obj.n_links;
n = obj.get_dim_configuration_space();
% obj.check_to_ith_link(n);
x_effector = obj.raw_fkm(q);
J = obj.raw_pose_jacobian(q);
Expand Down Expand Up @@ -314,7 +318,7 @@ function set_joint_type(obj, joint_type, ith_joint)
% both base and end-effector displacements (their default
% values are 1).

if nargin == 3 && ith < obj.n_links
if nargin == 3 && ith < obj.get_dim_configuration_space()
% If the Jacobian is not related to the mapping between the
% end-effector velocities and the joint velocities, it takes
% into account only the constant base displacement
Expand All @@ -338,7 +342,7 @@ function set_joint_type(obj, joint_type, ith_joint)
% This function does not take into account any base or
% end-effector displacements.

if nargin == 4 && ith < obj.n_links
if nargin == 4 && ith < obj.get_dim_configuration_space()
% If the Jacobian derivative is not related to the mapping between the
% end-effector velocities and the joint velocities, it takes
% into account only the constant base displacement
Expand Down Expand Up @@ -463,7 +467,7 @@ function dq_kinematics_plot(robot, q, varargin)
opt = plot_options(robot, varargin);
end

n = robot.n_links;
n = robot.get_dim_configuration_space();

if length(q) ~= n
error('Incorrect number of joints. The correct number is %d', n);
Expand Down Expand Up @@ -591,7 +595,7 @@ function dq_kinematics_plot(robot, q, varargin)
end

% Display cylinders (revolute each joint).
for i = 1:robot.n_links
for i = 1:robot.get_dim_configuration_space()
if opt.joints
%TODO: implement prismatic joints
N = 8;
Expand Down Expand Up @@ -641,7 +645,7 @@ function dq_kinematics_plot(robot, q, varargin)
% kinematic robot, and graphics are defined by the handle structure robot.handle,
% which stores the 'graphical robot' as robot.handle.robot.
function update_robot(robot, q)
n = robot.n_links;
n = robot.get_dim_configuration_space();

% Get the handle to the graphical robot. Since each kinematic robot
% stores just one graphical handle, if we want to plot the same robot
Expand Down Expand Up @@ -785,7 +789,7 @@ function update_robot(robot, q)
% simple heuristic to figure the maximum reach of the robot
if isempty(o.workspace)
reach = 0;
for i=1:robot.n_links
for i=1:robot.get_dim_configuration_space()
% Since the maximum reaching distance are given by the link offset
% and link length, we add them.

Expand Down
6 changes: 2 additions & 4 deletions robot_modeling/DQ_SerialManipulatorDH.m
Original file line number Diff line number Diff line change
Expand Up @@ -185,10 +185,8 @@
if(size(A,1) ~= 5)
error('Input: Invalid DH matrix. It must have 5 rows.')
end

% n_links
% TODO: change n_links to dim_configuration_space
obj.n_links = size(A,2);

obj.dim_configuration_space = size(A,2);

% Add theta, d, a, alpha and type
obj.theta = A(1,:);
Expand Down
4 changes: 1 addition & 3 deletions robot_modeling/DQ_SerialManipulatorMDH.m
Original file line number Diff line number Diff line change
Expand Up @@ -181,9 +181,7 @@
error('Input: Invalid modified DH matrix. It must have 5 rows.')
end

% n_links
% TODO: change n_links to dim_configuration_space
obj.n_links = size(A,2);
obj.dim_configuration_space = size(A,2);

% Add theta, d, a, alpha and type
obj.theta = A(1,:);
Expand Down
5 changes: 2 additions & 3 deletions robot_modeling/DQ_SerialWholeBody.m
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@
%
% See also DQ_kinematics, DQ_MobileBase

% (C) Copyright 2011-2019 DQ Robotics Developers
% (C) Copyright 2011-2023 DQ Robotics Developers
%
% This file is part of DQ Robotics.
%
Expand All @@ -71,7 +71,7 @@
% DQ Robotics website: dqrobotics.github.io
%
% Contributors to this file:
% Bruno Vihena Adorno - adorno@ufmg.br
% Bruno Vihena Adorno - adorno@ieee.org

classdef DQ_SerialWholeBody < DQ_Kinematics
properties (Access = protected)
Expand All @@ -86,7 +86,6 @@
% fkm of chain{ith} is its conjugate and the corresponding pose_jacobian is
% DQ.C8*J.
reversed;
dim_configuration_space;
end

methods
Expand Down
5 changes: 2 additions & 3 deletions robot_modeling/DQ_WholeBody.m
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
%
% See also DQ_kinematics, DQ_MobileBase

% (C) Copyright 2011-2019 DQ Robotics Developers
% (C) Copyright 2011-2023 DQ Robotics Developers
%
% This file is part of DQ Robotics.
%
Expand All @@ -62,7 +62,7 @@
% DQ Robotics website: dqrobotics.github.io
%
% Contributors to this file:
% Bruno Vihena Adorno - adorno@ufmg.br
% Bruno Vihena Adorno - adorno@ieee.org

classdef DQ_WholeBody < DQ_Kinematics
properties (Access = protected)
Expand All @@ -77,7 +77,6 @@
% fkm of chain{ith} is its conjugate and the corresponding pose_jacobian is
% DQ.C8*J.
reversed;
dim_configuration_space;
end

methods
Expand Down