• No results found

Navigation with variable point of reference for 3DOF differential drive mobile robot

N/A
N/A
Protected

Academic year: 2021

Share "Navigation with variable point of reference for 3DOF differential drive mobile robot"

Copied!
51
0
0

Loading.... (view fulltext now)

Full text

(1)

School of Innovation Design and Engineering

Västerås, Sweden

Thesis for the Degree of Master of Science in Engineering - Robotics

30.0 credits

NAVIGATION WITH VARIABLE POINT

OF REFERENCE FOR 3DOF

DIFFERENTIAL DRIVE MOBILE

ROBOT

Casper Adlerteg

cag16002@student.mdh.se

Adem Sen

asn14015@student.mdh.se

Examiner: Mikael Ekström

Mälardalen University, Västerås, Sweden

Supervisor: Lennie Carlén Eriksson

Mälardalen University, Västerås, Sweden

Company Supervisor: Jonas Larsson

ABB, Corporate Research

(2)

Contents

1 Introduction 3

1.1 Problem Formulation . . . 4

1.2 Limitations . . . 4

2 Background 4 2.1 Differential Drive Robot . . . 4

2.2 Kinematics . . . 6 2.2.1 Rotation Matrix . . . 6 2.3 Center of Mass . . . 7 2.4 MATLAB . . . 7 2.5 Gazebo . . . 7 2.6 ROS . . . 7 2.6.1 ROS Packages . . . 7 2.6.2 Rviz . . . 8 2.7 Path Planner . . . 8 2.8 Dynamic model . . . 8 3 Related work 8 3.1 Kinematics model . . . 8 3.2 Center of Mass . . . 9

3.3 Testing and Simulation . . . 9

4 Ethical and Societal Considerations 10 4.1 Societal Considerations . . . 10 4.2 Confidentiality . . . 10 5 Method 11 5.1 Methodology Outline . . . 11 5.2 Methodology Solution . . . 11 5.3 ROS System . . . 12 5.3.1 Gazebo . . . 13 5.3.2 TEB . . . 14 5.3.3 Test Cases . . . 16 5.4 Controller . . . 16

5.4.1 Turn Table Motion Reference Model . . . 17

5.4.2 External Navigation Point Motion Reference Model . . . 17

5.4.3 Odometry . . . 18 5.4.4 Test Cases . . . 18 5.5 Dynamic Model . . . 20 5.5.1 Inertia . . . 21 5.5.2 Center of Mass . . . 22 5.5.3 Newton forces . . . 22 5.5.4 Kane’s method . . . 23 5.5.5 Test Cases . . . 24 6 Results 27 6.1 Turn Table Motion Reference Model . . . 27

6.2 External Navigation Point Motion Reference Model . . . 31

6.3 ROS System . . . 36

6.4 Dynamic Model . . . 39

6.4.1 Newton forces . . . 39

(3)

7 Discussion 42

7.1 ROS System . . . 42

7.2 Turn Table Motion Reference Model . . . 42

7.3 External Navigation Point Motion Reference Model . . . 43

7.4 Dynamic Model . . . 43 8 Conclusions 45 8.1 Research Question 1 . . . 45 8.2 Research Question 2 . . . 45 9 Future Work 46 References 48

(4)

List of Acronyms

Robotic Operating System (ROS) Differential Drive Robot (DDR) Inverse Kinematics (IK)

Forward Kinematics (FK) Degrees of Freedom (DOF) Center of Mass (COM) Timed Elastic Band (TEB) State of the Art (SOTA) State of the Practise (SOTP) Wheeled Mobile Robot (WMR)

Application Programming Interface (API) Move Base Flex (MBF)

Turn Table Motion Reference Model (TTMRM)

External Navigation Point Motion Referenc Model (ENPMRM) Proportional-Integral-Derivative (PID)

(5)

Abstract

In this thesis, a kinematic model for controlling an Omni-directional 3 Degrees of Freedom (DOF) Differential Drive Robot (DDR) with an external navigation point is presented. Two different dynamic models for investigating the resulting torque on the three active motors on the robot are also developed and validated. The focus of the thesis is on the design of kinematic and dynamic models in an ideal environment and the kinematic model in a high fidelity environment. The kinematic model uses inverse kinematics to translate the controlling motion reference from the external navigation point to the three active motors on the DDR. The thesis also includes a comparison of the two different dynamic models based on Kane’s method and Newton’s second law of motion, respectively. The models presented in this thesis could aid autonomous robots with attached payloads such as hospital beds move with the centre of geometry as a focal point and thereby perform movements. The results show that such a kinematic model for controlling the specific robot is shown to be feasible in an ideal environment. However, due to Proportional–Integral–Derivative (PID) controllers for the active wheel motors not being exact enough, the model in the high fidelity environment does not perform correctly in all cases. Furthermore, the dynamic model results provide an understanding of the difference of torque dependant on the distance to the navigation point.

(6)

1

Introduction

Since 7% of work performed by hospital staff is transportation, automating transportation using DDR could increase time spent with patients [1]. Hiring additional personnel is an option but might not be economically feasible. Other industries such as food and clothing stocking companies also spend disproportional time relocating goods. This master thesis is a continuation of a project which created a DDR intending to offload such work.

The DDR have two wheels that are independent of each other where each wheel is bound to its own velocity and acceleration, meaning the left wheel can independently move forward while the right wheel moves backwards. This property exists due to each wheel having its own motor. The robot also has two passive wheel casters for balance. Due to this property, the DDR can obtain any orientation in the 2D plan. This makes them flexible, and mobile which is why they are used in different circumcises such as floor cleaning, payload transportation, autonomous wheelchair, to name a few [2][3][4]. In this paper, a DDR prototype developed by ABB Corporate Research with an extra motor controlling the top platform will be investigated, see Figure1. This extra plane should be able to navigate according to an external point, in Figure2athe red dot which represents the Center of Mass (COM) is moved outside and is now the External Navigation Point (ENP). The purpose is for the ENP to move along a trajectory and smoothly turn corners and avoid obstacles as if a trolley was attached. This can be seen in Figure 2b. The DDR uses Robotic Operating System (ROS)[5] to control the motors of the DDR.

ROS is a modular framework that provides packages and tools for controlling robots and other systems. Using ROS, nodes can be created for each subsystem which can then communicate with each other. DDR systems can use Inverse Kinematics (IK) and Forward Kinematics (FK) to control the robot position and orientation.

Figure 1: The DDR prototype developed by ABB Corporate Research seen from the side, where the red wheels represent the caster wheels. The grey half-circle means the actuator wheel, and the yellow square in the middle is the rotor which is connected to the base of the robot with the "turn table". This rotor gives the extra quality of rotating around that axis. These colours will represent the same thing throughout this report.

(7)

(a) Navigating with an external navigation point. (b) Navigating with regards to the trolleys COM.

Figure 2: Navigation with regards to the COM is represented by the red dot inside the robot. The red dot outside the robot is the external navigation point. The green dot is the desired position for the external navigation point, and the dotted line is the trajectory of the navigation point.

1.1

Problem Formulation

The goal of this Master thesis is to develop omni-directional navigation with a reference point located arbitrarily with respect to a 3 DOF DDR where the third axis controls the reference point. The reference point is meant to be used to navigate the robot with an attached trolley. Moreover, create a demonstration of the robot acting with the point of reference in simulation or real environment. To complete this goal, the following research questions must be answered.

• RQ1: Is it feasible to use a navigation point located arbitrarily with respect to the robot, and what challenges are there in the transformation of motion with regards to such a point? • RQ2: The intended 3 DOF setup results in a non-holonomic robot. This means that certain motion references might need some time to realize. What benefits does a dynamic model for controlling the robot offer in terms of motion and constraints?

1.2

Limitations

• Restricted to work with the ABB Corporate Research DDR prototype seen in Figure4

• The intended control system for the ABB Corporate Research DDR prototype will be imple-mented in Matlab and ROS together with Gazebo for simulation

• An attached trolley is itself omni-directional with only caster wheels, and the external nav-igation point can thereby move in an omni-directional manner as well

• The controlling motion reference is given in ˙ε = ( ˙x, ˙y, ˙θ)

2

Background

This section will cover the basic knowledge required to understand this thesis. The basics of the DDR will be covered along with the specifications of the software. Since ABB corporate research already designed a base of the DDR along with the software, the model in this project is restricted, as can be seen in section1.2.

2.1

Differential Drive Robot

DDR is perhaps the simplest mobile robot with only two active wheels. The two wheels are powered separately with two different motors and can therefore turn in different directions. The robot is also supported by a couple of idle wheel casters. This robot configuration makes it possible to turn around the midpoint by applying equal torque. [6]

(8)

This is the unicycle model see Figure3b. The DDR however, is based on two inputs which are the velocity of each wheel, as seen in Figure3a.

(a) Original model (b) Unicycle model

Figure 3: Figure3arepresent the model with regards to the speed of each wheel, where Vlef tis the

velocity of the left wheel and Vright the velocity for the right. Where Figure3brepresent the robot

with forward velocity and degree of rotation.

The kinematic model for such a configuration is well known and can be seen in equation (1) where r is the radius of the wheels and l is the distance between the actively powered wheels. The angular velocities of the right and left wheel are represented by ωR and ωL respectively. [7]

  ˙ x ˙ y ˙ θ  =   r/2 r/2 0 0 r/l −r/l   ωR ωL  (1) Considering a DDR, as described with equation (1) it can be seen that ˙y always is zero and therefore the DDR can never move in y-direction (sideways). Much like a car, it can drive forward and backwards but not directly sideways. This is the negative effect of non-holonomic wheels, also called non-holonomic constraints. [7]

A holonomic omni-directional platform is a mobile base with high manoeuvrability capable of moving in an arbitrary direction from the current configuration. Holonomic wheels, however, give the robot an omni-directional property, meaning it can turn in any direction within the 2D plane. This feature is almost always achieved with the use of special type driving wheels.[7]

The robot used in this work is a model of a DDR created by ABB Corporate Research and can be seen from the top in Figure4

(9)

Figure 4: Illustration of the Differential Drive Robot used in this paper. This robot configuration is constructed by ABB Corporate Research. The figure shows two actively powered wheels(grey), two wheel casters(red) and a rotation rotor in the middle(yellow).

As shown in Figure4, the DDR actuator wheels are placed on the edge of each side with one wheel caster in the front and one in the back. The standard DDR navigate in a 2DOF environment with one motor for each active wheel. The difference with the ABB DDR is the third motor which is added to rotate the turn table, which can be seen in Figure1. A robot that works with 3 motors like this one creates the 3DOF property. For flexibility, additional motors can be added in different kind of setups. The flexibility gets improved, but the DOF is still three, i.e. too many motors are used without increasing DOF, which will result in a complex and overconstrained system. [7]

2.2

Kinematics

To specify a certain robot orientation and position a kinematics model is created. Where forward kinematics refers to the process of computing the end position of a robot, given specified values for the joint parameter.

The inverse kinematics is the mathematical process of determining the joint parameters that provide the desired configuration for each of the robot end-effectors. Inverse kinematics is there-fore used to calculate the individual angle transformation of motions for each joint of the robot, to transform the robot from its starting to desired end configuration. [8]

2.2.1 Rotation Matrix

The rotation matrices are used for rotation around a single axis on a plane. The rotation matrices around axis x, y and z with an angle ρ can be seen in equations (2), (3) and (4) respectively. These matrices can then be combined to perform complex movements for 3DOF robots.

Rx(ρ) =   1 0 0 0 cos(ρ) −sin(ρ) 0 sin(ρ) cos(ρ)   (2) Ry(ρ) =   cos(ρ) 0 sin(ρ) 0 1 0 −sin(ρ) 0 cos(ρ)   (3) Rz(ρ) =   cos(ρ) −sin(ρ) 0 sin(ρ) cos(ρ) 0 0 0 1   (4)

(10)

2.3

Center of Mass

For smooth movement and control the COM is important, certain motion may prove unattainable depending on the weight and size of the trolley. Figure4 illustrates the ABB DDR. The COM is simple to find since the DDR is uniform, which would suggest the midpoint would be the COM. The same is not true when attaching to an object as seen in Figure5. The red dot in the center of the robot would have been the COM without the system as a whole. With the green dot representing the COM for the trailer, the COM for the unified system needs to be identified.

Figure 5: The robot attached to a trailer. Where the red dot represents the COM for the robot and the green dot represents the COM for the trailer.

When approximating the COM, parameters such as the weight distribution of the system and wheel specifications need to be taken into regard.[9] Also, because of these factors being so unreliable, the COM will give marginal errors.[10]

2.4

MATLAB

Matlab is a programming language with a primary focus on mathematics. Analyzing data and developing algorithms for different purposes, e.g. machine learning. Along with an editor, the software is integrated with a simulation environment called Simulink.

2.5

Gazebo

Gazebo is a well-designed simulator for robot development. It is a free, robust, community-driven simulator and offers the ability to simulate robots in complex environments. Gazebo also offers wide access to an array of features such as cloud simulating, high-performance physics engines, and plugins to provide direct access to Gazebo’s Application Programming Interface (API). [11]

2.6

ROS

ROS is a flexible framework with a collection of tools, libraries, and conventions for writing robot software. ROS was collaboratively built and designed for groups that are experts in specific fields to develop and build on each other work. The framework aims to simplify the creation of complex and robust robot behaviours. [12]

2.6.1 ROS Packages

Move_Base is a ROS package which, given a goal in the world frame, will attempt to reach it with a mobile base. The package links together a global and a local planner of any kind using the interface specified in the nav_core package. [13]

A more developed version of Move_Base exists as well called Move Base Flex (MBF). MBF is a backwards-compatible replacement for Move_Base, which can use existing Move_Base plugins and provides an enhanced version of the ROS interface. Along with providing detailed information about the current state of the robot and plugin feedback, it also allows for external executive logic to perform smart and flexible navigation strategies. MBF has successfully been deployed to control TORU robots in highly dynamic environments. [14]

(11)

2.6.2 Rviz

Rviz is a tool in ROS used for the visualisation of different models, e.g., robots, boats and aero-planes. Where commands and destination points can be sent, which the vehicle then tries to travel towards with the help of a planner. [15]

2.7

Path Planner

Timed Elastic Band (TEB) is a local planner that works towards finding the optimal trajectory. TEB is configured so that properties of the robot is taken into regard, i.e., holonomic or non-holonomic wheels. As well as configured properties, the user can customize different parameters for optimization of the trajectory and motion of the robot. [16]

2.8

Dynamic model

The use of dynamic models adds a more realistic representation when simulating vehicles or ma-chines where different parameters can be taken into regard, e.g. inertia, power consumption and viscosity.

3

Related work

Developing omni-directional robots can quickly become complex since there are many ways of creating them. This section will present similar projects, but with different robot configurations and with limitation outside the scope of this thesis work, but which still bear some relevance to this thesis.

3.1

Kinematics model

M.Wada et al. [7] developed two different solutions for an omni-directional robot. The first solution was a DDR with a third motor that controls the rotation of the turn table, similar to the ABB robot. Making it possible to rotate the robots turn table while rotating the robot platform in the opposite direction. The wheels can therefore change direction while the table looks motionless. The balance of the robot is assisted with two dual-wheel casters for stability, see Figure6.

Figure 6: Two caster wheels in the front and two motor-driven non-holonomic wheels in the back is used in the following project [7]

The kinematics of DDR was introduced in section 2.1 equation (1) As can be seen from the larger matrix, the y-axis gives full zeros, which indicate the non-holonomic robot. When applying the third motor to the system, the platform can turn while still moving in any direction, creating

(12)

movement in the y-axis as well. This creates the 3 DOF system, which then gives the kinematic seen in equation (5) with a reference system on the DDR platform midpoint.

  ωR ωL ωz  =       cosθ r − W sinθ 2rs sinθ r + W cosθ 2rs 0 cosθ r + W sinθ 2rs sinθ r − W cosθ 2rs 0 sinθ s − cosθ s 1         ˙ x ˙ y ˙ θ   (5)

The advantage with this method is the simplicity since the 3 DOF would result in 3 motors. This is contrasted with the second solution, where M.Wada et al. created four wheels with eight motors. Each wheel having 2 motors which make the robot overconstrained. One motor for the wheel rotation and one for the direction of the wheel. This creates great complexity for the wheels and higher consumption of electricity.

3.2

Center of Mass

Z.Shen et al. worked on shifting COM to an arbitrary point. The authors found this interesting due to robot payload and different solutions with mechanical arm operations. They started by creating their kinematics model of the so-called Wheeled Mobile Robot (WMR) robot, the model of WMR can be seen in Figure7.[17]

Figure 7: The WMR model with the actuator wheels in the back that generate momentum and the passive wheels in the front for steering. The dots position in the middle represents the COM.

The kinematics was done with respect to the uncertainty of different loads, and with the help of Lagrangian mechanics the dynamic model is derived. [17] The dynamic model is based on kinetic energy and is calculated with longitudinal velocity, angular velocity, mass, and inertia. Since the potential energy is equal to zero and the robot only moves in planar motion, which simplify the mathematics. To verify their results, both real-time experiments, as well as simulations, were conducted, with overall effective and feasible results. A substantial focus of the result was on known and fixed mass. The project also had solved parameters such as slipping/skidding uncertainties, actuator failures, input saturation, and output constraints, but with less focus.

F.N. Martins et al. present a DDR model split into a kinematic and a dynamic part. When considering the dynamic model specifications on actuators need to be analyzed, the authors invest-igate the inertia, electrical resistance of the motors, its mass, and much more. The analysis gives a clearer understanding of the impact of different speeds as well as accelerations. The dynamic model compared to the kinematic model result in a more precise simulation of the real robot behaviour. Their final result was a new approach on a velocity-based dynamic model for a DDR.[18]

COM is an important factor in different situations such as humanoid robots as well as robotic arm control H.Alai et al. gives an example of this. The authors move the COM with the help from the state estimator based on Kalman filter is designed for the humanoid robot. With marginal error, the authors look to improve this model. [19][20]

3.3

Testing and Simulation

To verify a model and its constraints and practicality, a simulation can be used. When simulating the problem, the use of Gazebo is an option where ROS acts as the task handler. A.Renawi et al. did just this in the paper [21] where a non-holonomic DDR was simulated and tested, with success.

(13)

Where the full kinematic and dynamic model was applied and even the current consumption of the motor could be simulated. When simulating, there will always be a marginal error which can be of different scale, all depending on the on the system. A.Renawi et al. specified motor torque, wheel mass, body mass without wheels, the inertia for both wheels and robot, and the size of the robot. With the help from all this, they could, with a small marginal error, estimate the real-time testing with the help from the simulated environment.[21]

4

Ethical and Societal Considerations

The research questions and methodology of this thesis does not pose any ethical considerations since the work is done in the private sphere without the use of any personal data. However, the impact on society resulting from this work is discussed in this section. The handling of ABB confidential data used in this thesis is also addressed here.

4.1

Societal Considerations

The work of automation is often framed in terms of job reduction which might pose negative economical consequences on a personal and societal level. However, decreasing human repetitive manual labor such as transportation in the health sector could lead to a higher amount of health worker to patient interaction and therefore increase the quality of care. It can also be assumed that not negligible portions of workplace accidents occur during the performance of transportation tasks. This technology, therefore, has the potential to not only increase the quality of care for patients but also increase the workplace conditions for health care professionals.

4.2

Confidentiality

This thesis work might handle confidential information owned by ABB Corporate Research which we are not allowed to release under a non-disclosure agreement. ABB will therefore approve the thesis paper before publication. Meaning some values and results might be non disclosed, but shown in a general form without losing context to the thesis project.

(14)

5

Method

This Master Thesis will follow the engineering methods six phases as specified by Ronald L.Lasser [22]. First is the idea phase in which the problem and the value are clearly defined as well as the feasibility of the work. The defining of the problem and value is fulfilled through the background and motivations, and problem formulation sections in this proposal and the feasibility through the initial time plan and limitations section. The next step is the concept phase which is about generating preferably several solutions to the problem. In this Master Thesis, the concept phase will consist of a literature study of possible solutions to the goal stated in the problem formulations section. The third phase is planning. Here the goal is to identify the tasks and task duration which are required to be completed. This phase will consist of creating a Work breakdown structure containing a priority of the importance of all tasks. After planning, the design phase starts. In this phase, all models and source code will be generated as well as any required modifications to the robot. In the development phase, experiments are performed. This is where the model is tested and validated. Preferably a simulation model with high fidelity will be developed for such tests and validations. The final phase is the launch phase. In this phase, the results will be compiled into an easily understandable format for presentation. Alongside all phases, documentation of the current work will be performed.

The methodology used in this master thesis work will be performed by implementing three different systems, and can is outlined in the list seen in section5.1.

5.1

Methodology Outline

1. Create a literary study of State of the Art (SOTA) and State of the Practice (SOTP) regard-ing:

• Kinematic models for omni-directional 3 DOF DDR • Dynamic models for omni-directional 3 DOF DDR

2. Create model based on Move_base and kinematic model for the 3 DOF DDR in a realistic environment using Gazebo and ROS

• Validate the kinematic model in the Gazebo simulation environment

3. Create kinematic model for the 3 DOF DDR in an ideal environment using Matlab • Validate the kinematic model using odometry to investigate the robots movement 4. Create kinematic model for the 3 DOF DDR with an external navigation point in an ideal

environment using Matlab

• Validate the kinematic model using odometry to investigate the robots movement 5. Create dynamic model for omni-directional 3 DOF DDR with a mass at the external

navig-ation point in Matlab

• Validate the dynamic model through investigating the required torque with different loads

• Validate the dynamic model through investigating the required torque with different rotation points between the robot and the external navigation point

5.2

Methodology Solution

Point 1. in section 5.1 is completed by a investigating the robotics field and related works in section2 and 3. Points 2. is solved by implementing a ROS system for the model according to Figure 8. This system is implemented to test the validity of the model in an environment with high fidelity to an actually physical system. The implemented system can be seen in section5.3

with the controller described in section 5.4.1. The same controller seen in section 5.4.1 is used to solve point3. The reason for this Matlab implementation is to test the purely validity of the

(15)

model in an environment without any external impact. When the validity of that model is ensured the external navigation point can be added. Point4 is created using the controller described in section5.4.2. The implementation and validation of this model will directly answer RQ1 seen in section1.1. The solution for the final step, point5is described in section5.5. The validity of this implementation answers the second research question RQ2 seen in section1.1.

Figure 8: The figure illustrates the intended ROS system using the controller described in section

5.4.1 with Gazebo, Rviz, TEB described in sections 5.3.1, 5.3.2.3 and 5.3.2 respectively. The

motor topics shown in the figure are the messages that communicate the desired velocity from the controller to the Gazebo simulation.

5.3

ROS System

The ROS network is shown in Figure9and contains three main modules, the controller, Gazebo and Move_Base. This system is implemented to validate the model with as high fidelity as possible to a real-world physical system. The controller receives a translation and a rotation from Move_Base and, using the method described in5.2translates the motion to motor references for left and right wheels and the turn table motor. Gazebo oversees the physical state of the robot, meaning the position and orientation of the links and joints as well as the relation between them. Move_Base receives the state of the robot and the environment, and using TEB path planner and a goal set by the user creates a motion for the robot to perform.

(16)

Figure 9: The figure represents the ROS nodes and topics that comprise the system and their relationship.

5.3.1 Gazebo

The ABB DDR mentioned in method was simulated as described in Gazebo, see the robot in Figure10.

Figure 10: The figure shows the 3 DOF DDR created by ABB Corporate Research in the Gazebo simulation environment.

The Gazebo ROS node receives velocities for left, right wheels and the turn table for the controller node. The first simulated model was implemented using the classic unicycle model.

Vr= V +

wL

(17)

Vl= V −

wL

2 (7)

With help from Rviz a destination could be chosen with an end pose. Move_Base then assisted by giving the robot the appropriate commands to reach the goal.

5.3.2 TEB

ROS has different software frameworks where rqt is one that assist in managing windows. By using the rqt plugin from ROS, rqt_reconfigure gets called in the terminal to adjust to the parameters appropriate for the task. After a functioning configuration is found, the values get stored in the teb_local_planner_params file.

5.3.2.1 Unicycle model

When testing the unicycle model the following parameters is adjusted: • maximum velocity in x

• weight for acceleration in x • maximum velocity in theta • weight for acceleration in theta • weight for non-holonomic property

The more weight a parameter have the more desirable that action will be. As mentioned in section

2.1 the unicycle model only drive in the local x-direction. Due to this, an increase of weights moving along the platforms x-direction is essential, i.e. making the local x-direction prioritized over the y-direction.

Weight for acceleration in theta focus on the acceleration in the x-direction of the platform, while weight for acceleration in theta is focusing on the rotation of the platform. From the unicycle model, the theta can be seen as the rotation, seen in Figure3b. Where parameter weight for non-holonomic property focus on moving as having non-non-holonomic wheels, i.e. having a high value in this parameter would rotate the platform of the robot and not the wheels. In Figure11the robot’s path will be according to the DDR configuration.

Figure 11: The figure shows the desired path in Rviz generated by TEB with Differential Drive configuration.

(18)

The green line is the desired trajectory for the robot. 5.3.2.2 Omni-DDR model

When testing the omni-DDR model the following parameters is adjusted: • maximum velocity in x

• weight for acceleration in x • maximum velocity in y • weight for acceleration in y • maximum velocity in theta • weight for acceleration in theta • weight for non-holonomic property

Compared to the unicycle model, which only moves in the platforms local x direction, the omni-DDR model needs to be given the property of moving in the y direction as well. Since the table heading is unbound from the platform. From Figure12the robot creates a path according to the newly modified parameters. The trajectory is now straight, which indicates that the robot will rotate on the spot or somewhere along the trajectory to get to the desired orientation at the goal position.

Figure 12: The figure shows the desired path in Rviz generated by TEB with omni-directional configuration.

5.3.2.3 Rviz

Rviz is used as the global path planner in the system. An end orientation is given by the user in Rviz. Using TEB a path for the robot is created. The path is made up of motion references for the robot at each point in time. Figure13shows a close up of the robot representation in Rviz with

(19)

separate coordinate systems for the active wheels, the turn table and global map. The relationship between these coordinate systems will determine the orientation of the robot.

Figure 13: Close up snapshot of the robot in Rviz, where each wheel orientation can be seen as well as the turn table and the global map axis.

5.3.3 Test Cases

To analyze the behaviour of the robot when using the ROS system, four test cases are created. The ROS system uses the Turn Table Motion Reference Model (TTMRM) described in section

5.4.1for these test cases. The first two test cases examine the behaviour of the robot in the ROS

system when given a motion reference in the turn tables y-direction with two different velocities. The two cases can then be compared to show the difference in behaviour. In the third test case, the controller is given a motion reference in the turn tables x direction. The last test case for the ROS system using the TTMRM validates the behaviour of the robot when given a purely rotational motion reference. With these tests, a correct robot behaviour can be confirmed. The results of these test cases are presented in section6.3.

5.4

Controller

Two different kinematic models for the controller are implemented. In order to test the validity of the system and the fundamental kinematics dictating the movement of the robot, a controller with the kinematics of an omni-directional DDR without an external navigation point is implemented. With such a model validated, kinematics for the navigation point can be added to the system, which has been confirmed to be acting correctly. This kinematic model is called TTMRM. The second kinematic model called External Navigation Point Motion Reference Model (ENPMRM) considers an external navigation point outside the robot. TTMRM is controlled with a motion reference for the turn table coordinate system, and ENPMRM is controlled with a motion reference for the external navigation point coordinate system.

(20)

5.4.1 Turn Table Motion Reference Model

Using the rotation matrix around the z axis Rz(ρ)shown in equation (4) and the motion reference

controlling the robot ˙εt= ( ˙xt, ˙yt, ˙θt), the translation and rotation for the platform ˙εp= ( ˙xp, ˙yp, ˙θp)

can be calculated, equation (8).

˙

εp= Rz(ρ) ˙εt (8)

The angle of the platform α is then calculated using linear velocities ˙xp, ˙yp, equation (9) and the

angular velocity of the platform ˙α is derived using the frequency of the local path planner ft, equation (10).

α = atan2( ˙xp, ˙yp) (9)

˙

α = αf t (10)

The magnitude of the platform velocity can be shown in equation (11) and along with the width between and radius of the differential drive wheel w, rw and the angular velocity of the platform

˙

αto calculate the motor reference for the right and left active wheels, equation (12),(13). ˙ ρ = sign( ˙xp) q ˙ x2 p+ ˙y2p (11) vright= ˙ρ + w 2α˙ (12) vlef t= ˙ρ − w 2α˙ (13)

5.4.2 External Navigation Point Motion Reference Model

The motion reference controlling the robot ˙εnp= ( ˙xnp, ˙ynp, ˙θnp)in ENPMRM is the desired motion

for the external navigation point O(1) in Figure14. The translation of motion from ˙ε

npin O(1) to

˙

εtin the turn table coordinate system O(2) is expressed in equation (14).

˙ εt=   cos(γ) sin(γ) 0 −sin(γ) cos(γ) 0 0 0 1    ε˙np+ ˙θ   −yr xr 0     (14)

Figure 14: The figure illustrates the relationship between the external navigation point O(1) and

the turn table O(2). The vector r is the arm connecting the external navigation point to the turn

table, γ is the angle at which the trolley meets the navigation point, and φ is the angle of the turn table.

(21)

5.4.3 Odometry

The position and pose of the robot for TTMRM is calculated from measuring the velocity of the motors Vright, Vlef t. ω is half the width between the two active wheels, and the angle of the

platform in the global coordinate system α is calculated by multiplying the angular velocity of the platform ˙α with the sampling frequency dt. The angular velocity ˙α is calculated using equation (15) and the velocity of the platform ˙ρ with equation (16).

˙ α = Vright− Vlef t 2ω (15) ˙ ρ =Vright+ Vlef t 2 (16)

Using the angle α and velocity ˙ρ of the platform the current x and y position of the platform in the global coordinate system is calculated using equations (17),(18) respectively. xp_old, yp_old

represent the x, y coordinates of the platform for the previous sample.

xp= ˙ρcos(α) + xp_old (17)

yp= ˙ρsin(α) + yp_old (18)

The linear velocities ˙xp, ˙yp, and the angular velocity ˙θ of the platform relative the global coordinate

system is derived using equation (19),(20),(21). ˙ xp= sign( ˙ρ) s ˙ ρ2 1 + tan(α)2 (19) ˙ yp= tan(α)2 (20) ˙ θ = ˙φ + ˙α (21)

The x,y coordinates for the external navigation point in ENPMRM xnp, ynpare calculated using

equation (22),(23) respectively where θ is the angle of the turn table relative the platform.

xnp= rcos(φ) + xp (22)

ynp= rsin(φ) + yp (23)

These data points are then compiled and plotted to evaluate the performance of the controller. 5.4.4 Test Cases

To analyze the behaviour of the robot when using the two controllers described in this section, test cases for producing distinct behaviours are used. For the TTMRM, the first test case validates the controller when moving only with a rotational movement. This is to show that the robot platform does not move in the x,y space when given only an angular velocity motion reference. A sketch of the intended movement for this test case is shown in Figure15a. Secondly, the robot’s behaviour when performing both a translation and rotation movement is validated. Two different test cases are produced, with the first test case giving the robot a translation motion reference in the turn tables y-direction, see Figure15b and the second with a translation motion reference in the turn tables x-direction see Figure15c. These test will ensure not only that the robot path is correct but also that the orientation of the robot when performing the motion is correct. The last test case for the TTMRM validates the behaviour of the robot when performing only translation motion. The test case is divided into two parts with separate motion references to show movement in both positive and negative directions. This test case is shown in Figure15d. The test cases for the ENPMRM are similarly designed with the first two test cases testing the behaviour of the robot when given a rotation and translation in x,y motion reference respectively, see Figures16a, 16b. The third test case validates the behaviour of the robot controller when given only translation motion reference. This test case is also separated into two sets to show the behaviour of the robot to show the movement in both positive and negative directions, shown in Figure 16c. The last

(22)

test case for the ENPMRM is performed with only a rotational motion reference to validate that the external navigation point doesn’t move in the x,y space, see Figure 16d. The results of the test cases for TTMRM are presented in section6.1and the results for ENPMRM are presented in section6.2. The results of the four test cases are for ENPMRM can directly answer the feasibility of using an external navigation in RQ1, section1.1. The results for the TTMRM does not directly answer the research questions, but a comparison between this model implemented in MATLAB and in the ROS system reveals challenges used to answer RQ1.

(a) Illustration of the first test case performed by TTMRM, where the robot platform does not move in the global x, y space while the external navigation point moves in a circle.

(b) Illustration of the second test case for TTMRM where the model is given a rotational and translation in y mo-tion reference.

(c) Illustration of the third test case for TTMRM where the model is given a rotational and translation in x mo-tion reference.

(d) Illustration of the forth test case for TTMRM. In this test case the robot only performs translation movement.

(23)

(a) Illustration of the first test case for ENPMRM where the model is given a rotational and translation in y mo-tion reference.

(b) Illustration of the second test case for ENPMRM where the model is given a rotational and translation in x motion reference.

(c) Illustration of the third test case for ENPMRM. In this test case the robot only performs translation move-ment.

(d) Illustration of the forth test case for ENPMRM. In this test case the external navigation point stays in the same global x, y position while the robot platform moves in a circle around it.

Figure 16: The figures show illustrations of the four test cases performed on the ENPMRM.

5.5

Dynamic Model

The Dynamic model is based on analyzing the DDR with inertia and mass added at the navigation point. The navigation point will then represent the COM for the robot together with the trolley. The robot has its own COM separated from the trolley. When a connection is made, and the robot becomes unified with the trolley (as in Figure17), the rotation point can be adjusted to investigate the behaviour. By testing different rotation points of the robot together with the trolley, the torque can be analyzed. The three different points that will be analyzed can be seen in Figure17.

(24)

Figure 17: The rectangle to the left represents the trolley with the COM marked with the green dot. The right circle is represented as the robot, where the red dot is the COM for the robot. A blue dot is placed in the middle to represent the COM for the entire system (trolley together with the robot).

Analyzing different torque could provide a more realistic result of information such as optimal trajectory, different speeds, shortest path and the strain on motors.

For simplification, the appearance of the trolley will always be rectangular, i.e. the Moment of Inertia (MOI) will always be the same. The MOI for the trolley can be seen in Equation30. The MOI will be applied when calculating the torque from Newton’s second law of motion; both linear and angular motion will be utilized see Equation24and25.

F = M a(linear) (24)

τ = Iα(angular) (25)

As mentioned in Figure17the red dot is the COM for the entire system, and to analyze different inertia at a different location Steiner’s theorem will be utilized, see Steiner’s theorem in Equation

26. The MOI for the blue dot and the green dot can be calculated for the unified system (trolley and robot together) with the help of Steiner’s theorem.[23]

Id = Icom+ M R2 (26)

Id represent the blue(or the green depending on what to rotate around) M is the mass of the

system, and R is the distance between Id and Icom, where Id is the MOI at the blue dot or green

dot.

ABB provided a dynamic model for a different purpose which was utilized with some alterations to serve some purpose in this project. The provided files could calculate the dynamic model for the DDR with a load on top of the robot. Parts for modelling the DDR without the load could be reused. The kinematics (from section5.4) is utilized to calculate the velocity of the wheels as well as the table angular velocity. To simplify the calculations for the dynamic model, values such as mass, height and width of the trolley are known.

5.5.1 Inertia

Since the values are known the inertia for the trolley respectively the robot can be calculated with the following equations27-30

Iwheel=

mwheelr2wheel

(25)

Abbreviation Description Iwheel inertia for each wheel

mwheel mass for each wheel

rwheel radius for each wheel

Itable inertia for the top table of the platform

Iplatf orm inertia for the platform

Itrolley inertia for the trolley

height height of the trolley width width of the trolley

Table 1: The table describe each property represented in equation27-30. m and r is explained for the wheel but not the rest, since these have the same meaning for the table, platform and trolley.

Itable=

mtabler2table

2 (28)

Iplatf orm =

mplatf ormrplatf orm2

2 (29)

Itrolley=

1

12Mtrolley(length

2+ width2) (30)

When rotating around the COM of the entire system(trolley together with the robot) the inertia can be added together as seen in equation31.

Itot= Iplatf orm+ Itrolley+ Itable (31)

Equation31will give a new unified COM for the entire system, which is described in section5.5.2. 5.5.2 Center of Mass

Since the COM and the mass of the trolley are known, the use of equation32will assist in locating unified COM. The COM position of the trolley is located with respect from the robot. Where the robot position always is in the origin, i.e. zero in both x and y axis.

unifiedcom=mrobotxrobot+ mtrolleyxtrolley

mrobot+ mtrolley (32)

Where xrobot represent the COM location of the robot and xtrolley is the COM location of the

trolley. Both locations are represented with an x and y coordinate. For Steiner’s theorem the inertia in the unified COM is needed, which is calculated from equation 31 and described in section5.5.1.

5.5.3 Newton forces

To calculate the torque for the third motor, i.e. the turn table. Steiner’s theorem is utilized to get the inertia for the third motor, located in the center of the robot. Described in equation33.

Icr= Itot+ Mtotd2cr (33)

Icr represent the inertia in the center of robot with respect to the COM of the entire system.

Where dcr is the distance from the COM to the third motor rotation point.

τtable= αtableIcr (34)

αfrom equation34represent the angular acceleration of the table. Which together with the inertia of the center of the robot gives the torque(τ) for the table.

For each wheel the force have a angular as well as a linear component. For the angular force equation 35 is utilized, where ˙ωplatf orm represent the angular acceleration of the platform and

(26)

˙

ωtable the angular acceleration of the table. Each angular velocity is then multiplied with the

inertia component (Icr). Which result in the force at the center of the robot.

Fangular = Icrω˙platf orm+ Icrω˙table (35)

The linear velocity is represented in equation 36where ˙Vl and ˙Vr is the acceleration for each

wheel. Vplatf orm is the forward velocity for the robot and Awheel represent the amount of active

wheels, i.e. the left and right wheel. The force for each wheel were added together with the force for the center. Which result in the linear force for the robot.

Flinear=

(rwheelIwheel( ˙Vl+ ˙Vr) + (MtotV˙platf orm))

Awheel (36)

The torque for each wheel is the resulting force for the angular as well as the linear force for each wheel multiplied with the radius for each wheel, i.e. rwheel. The angular force however needs

to be adjusted to each wheel therefore the inverse of rrobot needs to multiplied with Fangular for

the right and left wheel, seen in equations 37and 38. rrobot is the length from the center of the

robot to each wheel.

τright= rwheel( Flinear 2 + 2 rrobot Fangular) (37) τlef t= rwheel( Flinear 2 + −2 rrobot Fangular) (38) 5.5.4 Kane’s method

For calculation of the torque, Kane’s method is used with focus on motion. A mass matrix is created seen in equation39.

Mm=   Mtot 0 −CyrMr− CytMt 0 Mtot CxrMr+ CxtMt −CyrMr− CytMt CxrMr+ CxtMt MrCr2+ MtCt2+ Itot   (39)

Where Cr represent the COM for the robot and Cxr Cyr is the x respectively the y part, these

values are local for the robot i.e. they will always be zero. Ct represent the COM for the trolley

with respect to the robot.

To locate the angles for Cxt and Cyt (COM for the trolley) equation 39 is multiplied with the

rotation matrix i.e. equation4. Where ρ from equation 4is the angle between the direction of the platform compared to the direction of the table. Three matrices is created.

s1 =   0 0 −2sin(φ)Mtot 0 0 −2cos(φ)Mtot 0 0 −cos(φ)(CxrMr+ CxtMt) + sin(φ)(CyrMr+ CytMt)   (40) s2 =   0 0 2cos(φ)Mtot 0 0 −2sin(φ)Mtot 0 0 −cos(φ)(CyrMr+ CytMt) − sin(φ)(CxrMr+ CxtMt)   (41) s3 =   0 0 2(CxrMtot+ CxtMt) 0 0 2(CyrMtot+ CytMt) 0 0 0   (42)

Where φ represent the angle between the platform and the table of the robot.

These matrices (s1,s2 and s3) are used to create the speed matrix (S) by multiplying with the motion reference, i.e. the desired velocity which is represented with ˙ξ. In equation43 the speed matrix is created. Where the velocity is a vector which is represented by velocities in the table x direction, y direction and angular velocity θ. [24]

(27)

Then the mass matrix (Mm), robot acceleration ¨ξ and speed forces (S) together compute the

dynamic forces on the platform, seen in equation44. Fd=   Fd1 Fd2 Fd3  = Mmξ + S¨ (44)

With these forces we compute the torques according to equation45-47

τr= 1 2rw(Fd1+ w −1F d3) (45) τl= 1 2rw(Fd1− w −1F d3) (46) τt= Fd3 (47) 5.5.5 Test Cases

The tests with the dynamic model will all use the ENPMRM kinematics model since this model is modified for the scenario with a trolley. To analyze the different torques, test cases are created to inspect the behaviour. First, a trajectory is created where both a translation along a curved motion are analyzed. The analysis focuses on the torques needed to move with respect to the COM of the unified system compared to moving with respect to the COM at the trolley, see Figure17

for the two different comparisons where the blue dot represent the COM for the unified system and the green dot the scenario for the trolley. Figure18represent the trolley scenario. The trajectory is supposed to mirror a realistic problem, so the trajectory chosen is to push the trolley(navigation point) around a corner. This test scenario is chosen due to the strain created on the motors from this trajectory, where a difference will be seen from straight translation motion compared to rotation motion. To facilitate these scenarios, there will be no max torque, only the required torque for that instance. The scenarios will assume that the trolley have caster wheels.

These test will provide a difference in torque needed for certain rotational motions, which can give an understanding of a preferred navigation path. The results can be seen in section 6.4. Since there are two different dynamic models created, both of these will be tested in the same scenario as just mentioned and later compared in section7.4.

(28)

1 motion

2 motion

3 motion

Viewer does not support full SVG 1.1

Figure 18: Trajectory when rotating around the trolley COM. Red dot in the robot is COM for the robot and the green dot is the COM for the trolley. The red square is an object.

(29)
(30)

6

Results

This section presents the results from the experiments performed to validate the models described in section5.3,5.5.5and5.3.3. The results are analyzed and used to answer the research questions seen in section1.1. The first part will present the result from the motion references on the turn table with external navigation point as well as without. Afterwards, the results from the ROS system will be presented and lastly, the torque created from the dynamic model.

6.1

Turn Table Motion Reference Model

Figures19, 20, 21, 22 shows the global x,y coordinates of the path the TTMRM travels given a motion reference ˙εt = ( ˙xt, ˙yt, ˙θt). The red lines show the position of the robot. The green line

shows the position of the external navigation point, and the blue line is the arm connecting the robot and the navigation point. The model is validated by testing four distinct known cases using four motion references. The first case performed is with a pure rotational motion reference and can be seen in Figure19.

Parameter Description (x(np) t , y (np) t ) (1, 0) Sampling Time (dt) 1/20

Half width between active wheels (w) 0.3 (m) Table 2: Configuration parameters for the model.

(31)

Figure 19: The figure show the behavior of the model when given only a rotational motion reference i.e ( ˙xt, ˙yt, ˙θt) = (0.0, 0.0, 3.0). The table motors angular velocity ˙φ moves according to ˙θt. The

navigation point then travels along a circular path around the platform with a radius of the arm connecting the platform to the point.

The second test case is performed by giving the controller both translation in y-direction and rotation motion reference and can be seen in Figure20. The resulting path of the robot platform is a circle with the turn table orthogonal to the platform. Since the motion reference controlling the robot is given in the turn tables coordinate system, the 90◦angle of the turn table means that

(32)

-3 -2 -1 0 1 x coordinate -2 -1 0 1 2 y co ordinate

Turn Table Motion Reference Model

Navigation point Robot platform Robot arm

Figure 20: The figure show the behavior of the model when given a rotational, and translation in y-direction motion reference i.e ( ˙xt, ˙yt, ˙θt) = (0.0, 2.0, 2.0). The robot travels in a circular path

with an angular velocity of ˙θt with the turn table at an angle of 90◦to the heading of the platform.

Thereby also moving with a linear velocity in the y direction of the turn table.

The third test case seen in Figure 21 is performed with a x-directions and rotational motion reference. As a result the platform moves in a circle with the table angle the same as the heading of the platform.

(33)

-1.5 -1 -0.5 0 0.5 1 1.5 x coordinate -0.5 0 0.5 1 1.5 2 y co ordinate

Turn Table Motion Reference Model

Navigation point Robot platform Robot arm

Figure 21: The figure show the behavior of the model when given a rotational, and translation in x-direction motion reference i.e ( ˙xt, ˙yt, ˙θt) = (1.5, 0.0, 2.0)

The fourth test case seen in Figure22is performed with two pure translation motion references over 100 samples. The first 50 samples are given the reference ( ˙xt, ˙yt, ˙θt) = (2.0, 2.0, 0.0) produces

a 45◦trajectory. Since robot is not given any rotational motion reference the turn table angle will

stay at negative 45◦. The last 50 samples receive the motion reference ( ˙x

t, ˙yt, ˙θt) = (-2.0, 2.0,

0.0) produces the same behavior, but in the opposite x-direction giving an angle of 135◦. The turn

(34)

-1 0 1 2 3 4 5 6 x coordinate 0 1 2 3 4 5 6 7 8 9 10 y co ordinate

Turn Table Motion Reference Model

Navigation point Robot platform Robot arm

Figure 22: The figure shows the behavior of the model over 100 samples when receiving a motion reference of pure translation. The fist 50 samples are controlled with the motion reference ( ˙xt, ˙yt,

˙

θt) = (2.0, 2.0, 0.0) making the platform travel at a 45◦angle with the turn table at an equal, but

opposite angle. The last 50 samples receive a motion reference of ( ˙xt, ˙yt, ˙θt) = (-2.0, 2.0, 0.0)

making the platform travel at a 135◦angle with the turn table at -135◦.

6.2

External Navigation Point Motion Reference Model

Figures 23, 24, 25, 26, 27 show the path the ENPMRM travels in the global x,y coordinate system when given a motion reference ˙εnp = ( ˙xnp, ˙ynp, ˙θnp). The red line shows the path the

robot platform, the green line the path of the external navigation point and the blue line is the arm connecting the position of the external navigation point to the corresponding position of the platform. The model is validated by performing five distinct test cases with five different motion

Parameter Description (x(np) t , y (np) t ) (1, 0) Sampling Time (dt) 1/20

Half width between active wheels (w) 0.3 (m) Table 3: Configuration parameters for the model.

references. The first test case seen in Figure 23 is performed with a motion reference of both rotation and translation in external navigation points y-direction. This motion reference produces a behavior were the external navigation point moves in a circular path with the y-direction moving forwardly according to the motion reference ˙ynp = (1.0). The path is generated over 126 samples

(35)

until a full circle is completed. The robot itself can be seen to move in a circular path similar to the external navigation point, but with a wider radius at a orthogonal angle to the point.

-4 -3.5 -3 -2.5 -2 -1.5 -1 -0.5 0 x coordinate -2 -1.5 -1 -0.5 0 0.5 1 1.5 2 y co ordinate

External Navigation Point Motion Reference Model

Navigation point Robot platform Robot arm

Figure 23: The figure shows the behavior of the External Navigation Point Motion Reference Model controller for the 3DOF DDR. The robot is controlled using the rotational and translation motion reference of ( ˙xnp, ˙ynp, ˙θnp) = (0.0, 1.0, 1.0) over 126 samples.

Figure24 shows the second test case for the ENPMRM using the motion reference ( ˙xnp, ˙ynp,

˙

θnp) = (0.5, 0.0, 1.0). This motion reference produces a circular path for the external navigation

point with its x-direction moving forwardly according to ˙xnp= (0.5). The robot also moves in a

(36)

-2.5 -2 -1.5 -1 -0.5 0 0.5 x coordinate -1 -0.5 0 0.5 1 1.5 2 y co ordinate

External Navigation Point Motion Reference Model

Navigation point Robot platform Robot arm

Figure 24: The figure shows the behavior of the External Navigation Point Motion Reference Model controller for the 3DOF DDR. The motion reference used in this experiment is ( ˙xnp, ˙ynp,

˙

θnp) = (0.5, 0.0, 1.0) with the controller performing its path over 126 samples.

The third test case is controlled with two translation motion references over 75 samples each and is presented in Figure 25. For the first 75 samples the model is controlled with a motion reference of ( ˙xnp, ˙ynp, ˙θnp) = (1.0, 1.0, 0.0) which creates a diagonal path of 45◦for the navigation

point with the robot platform at a 90◦angle to the point. The last 75 samples is controlled with

the ( ˙xnp, ˙ynp, ˙θnp) = (-1.0, 1.0, 0.0) motion reference. This motion reference creates a -45◦diagonal

path for the external navigation point. The robot platform moves in parallel path with -90◦angle

(37)

-1 0 1 2 3 4 5 6 7 8 x coordinate -1 0 1 2 3 4 5 y co ordinate

External Navigation Point Motion Reference Model

Navigation point Robot platform Robot arm

Figure 25: The figure shows the behaviour of the External Navigation Point Motion Reference Model controller for the 3DOF DDR. For this behavior test the robot is controlled by a motion reference of ( ˙xnp, ˙ynp, ˙θnp) = (1.0, 1.0, 0.0) for the first 75 samples. The external navigation point

then moves diagonally at a 45◦angle with the robot platform parallel to it. The second segment of 75 samples uses a motion reference of ( ˙xnp, ˙ynp, ˙θnp) = (-1.0, 1.0, 0.0) and produces a movement

for the external navigation point of -45◦again with the platform parallel. During the first samples of the second segment, the external navigation point can be seen to rotate down to its new position relative to the platform.

The fourth test case seen in Figure 26 is performed over 126 samples. The model is given a motion reference of pure rotation at ( ˙xnp, ˙ynp, ˙θnp) = (0.0, 0.0, 1.0). The robot moves in a circular

path with 1 in radius while the navigation point stays in the same position and only moves with in rotational movement of ˙θnp = (1.0).

(38)

0 0.5 1 1.5 2 x coordinate -1 -0.5 0 0.5 1 y co ordinate

External Navigation Point Motion Reference Model

Navigation point Robot platform Robot arm

Figure 26: The figure shows the behaviour of the External Navigation Point Motion Reference Model controller for the 3DOF DDR when given a pure rotational motion reference. ( ˙xnp, ˙ynp,

˙

θnp) = (0.0, 0.0, 1.0). The motion is performed over 126 samples until the resulting path for the

platform creates a full circle. For the first to the second sample the robot can be seen to perform an adjustment to be able to perform the circular motion correctly.

The fifth test case seen in Figure27is also performed with a pure rotational motion reference, but with a lower angular velocity and a higher amount of samples than test case four. The motion reference in this case is ( ˙xnp, ˙ynp, ˙θnp) = (0.0, 0.0, 0.1) over 1258 samples to from a complete circle

(39)

0 0.5 1 1.5 2 x coordinate -1 -0.5 0 0.5 1 y co ordinate

External Navigation Point Motion Reference Model

Navigation point Robot platform

Figure 27: This figure shows the behaviour of the External Navigation Point Motion Reference Model controller for the 3DOF DDR. The controller is again given a pure rotational motion reference as seen in Figure21, but with the lower velocity of ( ˙xnp, ˙ynp, ˙θnp) = (0.0, 0.0, 0.1). The

motion is performed over 1258 samples to create a full circle for the path of the robot platform. The blue line connecting the position of the external navigation point with its corresponding platform position is not included in this figure so as to easier see and interpret the resulting paths.

6.3

ROS System

The following Figures28, 29, 30, 31 show the starting and end position of the robot when per-forming the test cases described in section5.3.3. The end position in Figures28,29is the position of the robot when it has oriented itself in a stable position and can start moving along the turn tables y axis. The end position in Figures30, 31is the position the robot has after moving in a short time interval.

(40)

(a) Starting position for the 3 DOF DDR when performing the first test case.

(b) End position for the 3 DOF DDR when perform-ing the first test case.

Figure 28: Figures 28a, 28b show the start and end position for the 3 DOF DDR using the TTMRM. In this test case the robot is performing the adjustment movement required to perform the given motion reference ( ˙xt, ˙yt, ˙θt) = (0.0, 1.0, 0.0).

(a) Starting position for the 3 DOF DDR when per-forming the second test case.

(b) End position for the 3 DOF DDR when perform-ing the second test case.

Figure 29: Figures 29a, 29b show the start and end position for the 3 DOF DDR using the TTMRM. The figures show the adjustments done by the robot when performing the second test case with the motion reference ( ˙xt, ˙yt, ˙θt) = (0.0, 0.1, 0.0)

(41)

(a) Starting position for the 3 DOF DDR when perform-ing the third test case.

(b) End position for the 3 DOF DDR when perform-ing the third test case.

Figure 30: Figures 30a, 30b show the start and end position for the 3 DOF DDR using the TTMRM. The figures show the movement of the robot in a short time interval when performing the third test case with the motion reference ( ˙xt, ˙yt, ˙θt) = (1.0, 0.0, 0.0)

(a) Starting position for the 3 DOF DDR when perform-ing the forth test case.

(b) End position for the 3 DOF DDR when perform-ing the forth test case.

Figure 31: Figures 31a, 31b show the start and end position for the 3 DOF DDR using the TTMRM. The figures show the movement of the robot in short time interval when performing the forth test case with the motion reference ( ˙xt, ˙yt, ˙θt) = (0.0, 0.0, 10.0). When performing this test

(42)

6.4

Dynamic Model

This section is divided in to two parts since there was two different dynamic models tested. The first one which is based on Newton second law of motion and the second one based on Kane’s method. The resulting trajectory of the robot for both scenarios can be seen in Figures32band

32a. 0 0.5 1 1.5 2 2.5 3 x [meter] -1 -0.5 0 0.5 1 1.5 2 y [meter] Robot trajectory Robot platform NP Robot arm

(a) Trajectory for center of trolley

0.2 0.4 0.6 0.8 1 1.2 1.4 1.6 1.8 2 x [meter] -0.6 -0.4 -0.2 0 0.2 0.4 0.6 0.8 1 1.2 y [meter] Robot trajectory Robot platform NP Robot arm

(b) Trajectory for COM at unified system

2.22 2.225 2.23 2.235 2.24 2.245 2.25 2.255 2.26 x [meter] -0.03 -0.02 -0.01 0 0.01 0.02 0.03 0.04 y [meter] Robot trajectory Robot platform NP Robot arm

(c) A snapshot at the navigation point at the beginning of the rotation from Figure32a.

1.842 1.844 1.846 1.848 1.85 1.852 1.854 1.856 1.858 1.86 1.862 x [meter] -0.01 -0.005 0 0.005 0.01 0.015 0.02 y [meter] Robot trajectory Robot platform NP Robot arm

(d) A snapshot at the navigation point at the beginning of the rotation from Figure32b.

Figure 32: The red line represents the position of the robot, and the green represents the navigation point, the trajectory follows the motions from Figure18. The blue line is the distance between the robot and the navigation point at the moment in time.

The motion reference given was ( ˙xnp, ˙ynp, ˙θnp) = (-1.0, 0.0, 0.0) for the movement in x direction.

Afterwards a rotation was made with the following motion ( ˙xnp, ˙ynp, ˙θnp) = (0.0, 0.0, 0.5). Ones

the rotation of 90◦is met a translation with a motion reference of ( ˙x

np, ˙ynp, ˙θnp) = (-1.0, 0.0, 0.0)

was given.

6.4.1 Newton forces

The results in this section are based on the implementation part from section 5.5. The three following Figures 33a, 33b and 33crepresent the torque for each motor, i.e. the torque for left, right and table motor. The figures represent two different curves, one blue, which is the torque around the COM for the trolley. The red second curve represents the unified COM, as was explained in section5.5.5. The distance from the robot to the unified COM and from the robot to the COM of the trolley is 0.48 respectively 1.0 meters. The torque from the trajectories in Figure32, will be presented in Figure33. Figure 33a represent the torque for the left wheel motor, while following the trajectory of Figure32. Where the right wheel motor can be seen in Figure33b and the table torque can be seen in Figure33c.

(43)

0 1 2 3 4 5 6 Time [s] -200 -150 -100 -50 0 50 100 Tor que [N/m]

Torque for left wheel

COM at unified system COM at trolley

(a) Torque for left wheel

0 1 2 3 4 5 6 Time [s] -200 -150 -100 -50 0 50 100 Tor que [N/m]

Torque for right wheel

COM at trolley COM at unified system

(b) Torque for right wheel

(c) Torque for table

Figure 33: The figure represent the amount of torque acting on the left, right and turn table motors respectively when performing test case motion seen in Figure18. The y-axis represents the torque, and the x-axis represents the time. The blue line represents the torque when the navigation point is stationed at the trolleys COM, i.e. the blue dot in Figure 17. The red line is the torque for the COM of the unified system, i.e. the red dot from Figure17.

6.4.2 Kane’s method

The results in this section is based on the implementation from section5.5. Figure34 represent table torque as well as left and right motor torque.

(44)

0 1 2 3 4 5 6 Time [s] -30 -20 -10 0 10 20 30 Tor que [N/m]

Torque for left wheel

COM at unified system COM at trolley

(a) Torque for left wheel

0 1 2 3 4 5 6 Time [s] -50 -40 -30 -20 -10 0 10 20 30 Tor que [N/m]

Torque for right wheel

COM at trolley COM at unified system

(b) Torque for right wheel

0 1 2 3 4 5 6 Time [s] -250 -200 -150 -100 -50 0 50 100 150 200 250 Tor que [N/m]

Torque for turn table

COM at Trolley COM at unified system

(c) Torque for table

Figure 34: This figures represent the torque from Kane’s method, the same scenarios as presented in Figure33.

(45)

7

Discussion

In this section the results seen in section6and the significance of the Master Thesis as a whole will be discussed. The first part will cover the work and problems encounter from the ROS system. The second and third part will attend to the challenges from the TTMRM as well as the ENPMRM. Lastly the advantages of having a dynamic model will be presented.

7.1

ROS System

The model for controlling the 3 DOF Omni-directional DDR with motion reference for the turn table simulated in Gazebo using the ROS system described in section 5.3 has some apparent problems. When testing the DDR setup with TEB and the table rotated at 180◦, the robot

believed that backwards was forward. This could be seen when the robot started driving in the opposite direction. This prove that some integration between TEB and ROS where not fully completed.

Given a motion reference purely in the turn table y-direction while in the initial robot position, the turn table as seen in Figures28, 29is expected to stay in the same global position while the robot platform rotates 90◦. Then when the robot has performed this adjustment it should start

its translation motion in the turn tables y-direction. However, in both these cases, the robot turn table and platform are unsynchronized, and the rotation motion stops when the turn table is at 90◦to the platform no matter at what orientation the platform is at. In the controller, the angular

velocity of the turn table in such a case is set to the negative angular velocity of the platform, i.e. the turn table should not move in its global position. The reason for this incorrect motion seems to be that the PID controller does not give the same actual angular velocity for the platform and the turn table. This produces an unsynchronized behaviour when the platform and turn table should have the same angular velocity.

When the model is given a motion reference purely in the turn tables x-direction when the robot is in its initial orientation, the correct motion is performed as seen in Figure30. The robot also produces the correct behaviour when given a purely rotational motion reference, as seen in Figure

31.

In this test case, it can be seen that only the turn table rotates with an angular velocity equal to that of the motion reference. These results are not significant to the first part of RQ1 since the TTMRM was not shown to be working correctly in this environment with high fidelity to the real world, and therefore the ENPMRM could not be tested. However, these results are used to analyze challenges in transformation of motion as described in the second part of RQ1. Furthermore, a clear basis for implementation in a real-world system is shown.

7.2

Turn Table Motion Reference Model

The model for controlling the 3 DOF omni-directional DDR with motion reference for the turn table performs correctly. The first test case seen in Figure19is controlled with a purely rotational motion reference and produces a pure rotational motion for the turn table. In this case, there are three possible solutions. The first is with a still platform with the turn table motor rotating at the angular velocity given by the motion reference. The second solution is that the turn table motor does not move while the platform rotates around its z-axis with the angular velocity given by the motion reference. The third possible solutions is a combination of the two. The solution performed by the model in this test case is the first solution explained. The controller can be modified by adding logic to produce a preference for one of these three solutions.

The second and third test case seen in Figure20,21respectively both produces circular paths for the robot platform. The translational component of the motion reference in the second test case is in the y-direction for the turn table coordinate system. As predicted, the platform performs a circular path with the turn table in a 90◦angle to the platform, i.e. the robot is moving in the turn

tables y-direction. This proves that the failed adjustment in y-direction described in section7.1is not caused by the kinematics of the model.

The third test case is the same as test case two, but with the translational component of the motion reference given in the turn tables x-direction. As predicted, this produces the same behaviour as

Figure

Figure 2: Navigation with regards to the COM is represented by the red dot inside the robot
Figure 3: Figure 3a represent the model with regards to the speed of each wheel, where V lef t is the velocity of the left wheel and V right the velocity for the right
Figure 5: The robot attached to a trailer. Where the red dot represents the COM for the robot and the green dot represents the COM for the trailer.
Figure 6: Two caster wheels in the front and two motor-driven non-holonomic wheels in the back is used in the following project [7]
+7

References

Related documents

Keywords: oral lichen planus, oral mucosal lesion, epidemiology, levothyroxine sodium, thyroid disease, hypothyroidism, autoimmune thyroid disease, antithyroid antibodies,

sification system simple and easy to use.. Suitable type of compaction equipment for different groups of soils I. Silt, silty soils, IV, fill and clayey sand and gravel

This allows us to assess the fraction of the total hous- ing stock that is listed, and to condition observed listing propensities on functions of the predicted sales price, such as

Chapter 1 provides an introduction to this project, some general information about SCADA systems, cyber-attacks that have been done on these systems and some information about

In order to evaluate the capabilities of the discrete and continuous control agents on the task of navigating a mobile robot in human environments, the performance of both approaches

Calculus Demystified Chemistry Demystified College Algebra Demystified Databases Demystified Data Structures Demystified Differential Equations Demystified Digital

The extension to the notion of reference is now fairly obvious: a deflationary theory of reference is one that takes a more or less trivial schema, like “‘a’ refers to

• In order to address the described mobile challenges by an architectural solution and help a software archi- tect during the design of a software architecture for a mobile