• No results found

Peg-In-Hole Insertion of Industrial Workpieces

N/A
N/A
Protected

Academic year: 2021

Share "Peg-In-Hole Insertion of Industrial Workpieces"

Copied!
59
0
0

Loading.... (view fulltext now)

Full text

(1)

Computer Engineering C, B.Sc Thesis, 15 Credits

Peg-In-Hole Insertion of

Industrial Workpieces

Tobias Lans och Bobo Lillqvist

Computer Engineering Programme, 180 Credits

Örebro, 6th Semester 2019

Examiner: Dr. Henrik Andreasson

Peg-In-Hole Insertion of Industrial Workpieces

Örebro Universitet Instutitionen för naturvetenskap och teknik 701 82 Örebro

Örebro University School of Science and Technology

(2)
(3)

Sammanfattning

Denna rapport täcker arbetet och resultatet av en högnivåkontroller för en robo-tarm som besitter intentionen att montera ett cylinderformat verktyg i ett cirkulärt hål, så kallad peg-in-hole. Detta åstadkoms genom att implementera en kontroller som ett ROS paket. Styrning av roboten gjordes med hjälp av en impedans kon-troller och kraftavläsning användes som externa sensorer för guidning av roboten. Utvecklingen gjordes både i simulering och på en riktig robot. Implemtationen visade sig vara lyckad att utföra uppgiften med hänsyn till de satta kraven. För-bättringspotentialen är bättre kraftavläsning samt ett tillägg av externa sensorer för en förbättrad avläsning av robotens omgivningen.

(4)
(5)

Abstract

This thesis covers the work and result of a high level controller for a robot arm with the intention of inserting a cylinder shaped tool into a circular hole, a so called peg-in-hole insertion. This was done by implementing a controller as a ROS package. An impedance controller was used for controlling the robot and force feedback readings as external senses for guiding the robot tool. Development was done in simulation and on a real robot. The implementation proved to be successful at performing an insertion in regards to the set requirements, with the potential improvements being a better force reading as well as added external senses for improved environmental perception.

(6)
(7)

Contents

Sammanfattning . . . i Abstract . . . ii List of Figures . . . v List of Tables . . . v List of Listings . . . v 1 Introduction 1 1.1 Background . . . 1 1.2 Project . . . 1 1.3 Requirements . . . 2 1.4 Development method . . . 3 2 Peg-In-Hole Insertion 5 2.1 Why is This a Difficult Task for a Robot? . . . 5

2.2 Force Interpretation . . . 6

2.3 Impedance Control and Compliance . . . 7

2.4 Previous Work . . . 8

3 Architecture 9 3.1 ROS (Robotics Operating System) . . . 9

3.2 State Machine Design . . . 10

3.3 Concurrency . . . 11

3.4 System Overview . . . 11

4 Method and Tools 13 4.1 Programming Languages and Libraries . . . 13

4.1.1 C++ Libraries . . . 13 4.2 Tools . . . 14 4.2.1 ROS . . . 14 4.2.2 Gazebo . . . 14 4.2.3 rviz . . . 14 4.2.4 The Robot . . . 14

4.2.5 Other Applications Used for Development . . . 15

5 Implementation 17 5.1 ROS Node . . . 17

(8)

5.2 State Machine . . . 21

5.2.1 Move to Initial Position . . . 22

5.2.2 Downward Movement . . . 23

5.2.3 Spiral Motion . . . 25

5.2.4 Wiggle . . . 27

5.3 Controlling the Robot . . . 29

5.3.1 Simulation . . . 29

5.3.2 Working on the Robot . . . 30

6 Result 31 6.1 The Sufficient Solution . . . 31

6.1.1 Test Runs . . . 31 6.1.2 State Machine . . . 33 6.1.3 Limitations . . . 35 7 Discussion 37 7.1 Requirements . . . 37 7.1.1 Primary . . . 37 7.1.2 Secondary . . . 38

7.2 Social and Financial Implications . . . 39

7.3 Further Work . . . 39

8 Reflection 41 8.1 Skills and Abilities . . . 41

8.1.1 ROS . . . 41

8.1.2 Working with Hardware . . . 41

8.2 Knowledge and Understanding . . . 42

8.2.1 Scientific Papers . . . 42

8.3 Evaluation Ability and Approach . . . 42

References . . . 45

Appendices 47

A Franka Emika Panda Datasheet 47

(9)

List of Figures

1.1 Template used for hand held drilling . . . 2

2.1 Force interpretation example of a peg sliding over a hole . . . 6

2.2 Impedance controller model . . . 7

3.1 General ROS workflow . . . 10

3.2 High level diagram of the finite state machine . . . 10

3.3 Asynchronous execution of the tasks in the controller . . . 11

3.4 Diagram showing an overview of the system . . . 12

5.1 High level description of the ROS node . . . 18

5.2 Sequence diagram showing execution of a state . . . 19

5.3 Insertion node publishing to topics that robot node is subscribing to 19 5.4 Insertion node subscribing to topics that the robot node is publish-ing to . . . 20

5.5 Side view of the insertion process from the perspective of the state machine . . . 21

5.6 Forces acted upon the x, y and z-axes of the robots tool tip at an instance when the peg is making contact with the floor . . . 24

5.7 Plotting of spiral trajectories with and without evenly spaced points 26 5.8 Rviz 3D visualization environment used for visualizing the simula-tion of the panda robot . . . 29

6.1 Test run of the insertion process . . . 33

List of Tables

6.1 Result of 21 insertion attempts . . . 32

List of Listings

1 State machine implementation as a basic switch . . . 22

2 Generatinging a linear trajectory . . . 23

3 Generate Archimedean spiral . . . 25

4 Conversion between pose massage and transformation matrix . . . 28

(10)
(11)

Chapter 1

Introduction

This chapter will serve as an introduction and explanation of the project for this thesis. It will cover the background that explains the reason the project exists, an explanation and overview of the actual project, the requirements the project must meet and finally an explanation for the development method used throughout the project.

1.1

Background

The purpose of this project is to study solutions for inserting a circular peg in a hole. This is done using a robotic arm with lower accuracy than the clearance of the hole and with an uncertainty of the hole position.

The employer of this project is the Center for Applied Autonomous Sensor Systems (AASS) which is a research environment on autonomous systems, robotics and artificial intelligence. AASS also works in collaboration with industrial organizations and companies. AASS was contacted by SAAB to investigate a solution for automation of drill assembly using a robotic arm with lower precision than the clearance of the hole would demand.

The idea behind this thesis comes from a former bachelor thesis for SAAB that looked in to the problem of automating drilling on SAAB air crafts [1]. The drilling is today done manually with a hand held drill that is being inserted into a template for accuracy. The thesis suggested that this process could be done by a robotic arm.

1.2

Project

The work to be done is to implement a controller that can perform a peg-in-hole insertion into a circular hole with 0.05 mm clearance by a robotic arm that has

(12)

template of the holes that are used for hand held drilling. The images is showing both chamfered and chamferless holes.

Figure 1.1: Template used for hand held drilling.

With very low hole clearance it is unlikely for the robotic arm to insert the drill into the template hole even if the robot is given an exact coordinate of the hole. Therefore a controller that increases said likelihood is desired in order to automate the insertion process.

The controller to be implemented will be running a finite state machine which handles the order of execution. The basic steps of the insertion algorithm will be executed by a corresponding state of the state machine. The state machine will run until the insertion is completed.

1.3

Requirements

In order to design and implement a sufficient high-level controller that can go through all the sequences of the state machine and accomplish the goal of per-forming a peg-in-hole insertion within a reasonable time and with an acceptable rate of success. For a sufficient solution, the following requirements exists:

(13)

The solution needs to

• perform tool insertion with no added uncertainty to the hole center, • have an insertion success rate of about 50 % and

• not let the time of the insertion process take longer than three minutes. The first goal with no added uncertainty exists due to the fact that added uncertainty would add complexity that the initially agreed upon conditions did not require. The peg should start as close to the hole as possible, and if the controller can perform a full insertion from that point, it is a success.

The 50 % success rate is not a request from SAAB, but rather a relatively arbitrary set threshhold. It’s an incarnation of the sense that it works a sufficient amount of times.

The three minutes insertion time comes from experience of having seen other similar peg-in-hole insertions and seeing that on average it can take anything from 1.8 seconds to 8 minutes. A three minute time seemed to be a realistic starting point.

A desirable case, but not a requirement, would be to improve upon the initial solution by solving or implementing one or several of the following cases:

• Develop an understanding and solve the problem of the peg getting jammed in the hole.

• Test the controller with different uncertainties of hole position. • Test the solution on both chamfered and chamferless holes.

• To have the implemented states functional with appropriate reset or fail states for each of the states.

1.4

Development method

The work was done in a pair of two. The work was divided when it made sense and the tasks were distributed to who was most knowledgeable and comfortable with that particular task. Therefore there was no intentional set of responsibilities throughout the project. The tasks were interchangeably done. Most programming

(14)

with a Kanban board to structure the work. This process however was not particularly disciplined due to the relatively small size of the project, the limited time frame of ten weeks and there only being two members on the project. Following a disciplined methodology would have been more apt for a larger project with more members. In this case it would have been inefficient due to the fact that the progress was equally understood by the entire team throughout the project.

(15)

Chapter 2

Peg-In-Hole Insertion

The task of inserting a tool into a hole is in robotics called a peg-in-hole insertion problem. This chapter intends to explore and explain this concept, including why it is difficult, how the thesis in particular chose to solve it and what has been written about it previously.

2.1

Why is This a Difficult Task for a Robot?

Humas are from an early age able to easily perform the task of inserting a tool into a hole. Humans possesses several cognitive skills to help accomplish this task, some of these skills are:

• vision that helps to identify the position and shape of the peg and the hole, • motor skills to move and orient the peg and

• perceptive abilities that allow humans to feel the different forces and to then judge e.g. whether or not the peg is on the surface or touching any part of the hole.

A robot can be equipped or programmed to posses these skills. It can be mounted with a camera for vision, given a controller for motor skills and granted a force reading tool to sense the forces being exerted unto it. However the problem is making sense and interpret this data.

The output of the forces are data that can be recorded from the robots tooltip and joints. The amount of force observed implies the state of the peg-in-hole insertion process. A force on the z-axis would perhaps imply ground contact. But the quantity is harder to read and make sense of, especially with a demanding clearance. This data has to be used correctly to adjust the movement of the robot proportionally to the desired movement. For a human, this comes naturally, for a robot it has to be designed.

(16)

2.2

Force Interpretation

Reading and understanding the forces from the peg-in-hole insertion is an impor-tant part for implementing a working solution. For performing a blind insertion, the forces acts like the sight and senses of the robot and can be mapped to a location of the search space or used as a trigger to continue to the next step in the algorithm.

A hypothetical example is shown in Figure 2.1. When the peg makes contact with the hole the force reading is register a drop. This reading can be mapped as a condition for moving on to the next phase of the insertion process.

(a) Peg sliding towards the hole. (b) Hole contact.

(c)

Figure 2.1: An example of a peg sliding over a hole. The blue and red arrow in (a) and (b) is showing the movement and downward force of the peg. The graph in (c) shows the drop at time 1.0 and contact inside the hole at time 2.0.

(17)

2.3

Impedance Control and Compliance

This peg-in-hole insertion problem with a demanding hole clearance is a contact-rich task that requires the robot manipulator to directly interact with its en-vironment. To be able to control the robot in the contact-rich environment in this project, an impedance controller was used in simulation and on the real robot.

An impedance controller models a dynamic relationship between the end effector and the desired goal point [2]. The controller models a virtual spring which will try to move the end effector towards the goal. By doing this, calculating the inverse-kinematics between the end effector and the goal point, which could be computationally demanding, can be avoided. The model is a spring-damper system which could, on a high level, be expressed by the equation

F = D( ˙xd− ˙xa) + K(xd− xa) (5)

where D is the damping constant, K is the spring constant, xa and xdis the actual

and the desired end effector position in Cartesian space and F is the contact force [3, (eq. 5)]. Figure 2.2 shows the model on a robot arm.

Figure 2.2: Impedance controller model.

Using this kind of force-feedback controller, the end effector can be compliant to obstacles. A non-compliant robot would try to execute the given trajectory even if it would encouter an obstacle. The variables of the impedance controller can be adjusted to regulate stiffness and damping in position and orientation. Setting a low stiffness could yield the end effector to be compliant in any desired direction. This can be very helpful for assembly tasks since the compliance can be used to e.g. detect hole contact, as described previously in section 2.2.

(18)

2.4

Previous Work

The problem of high precision tool assembly using robotics has been studied for a long time. In a paper from 1987 [4], Whitney describes the main problems of contact tasks and presents several force-feedback architectures including impedance control, damping control and stiffness control. Whitney compares the strategies for different problems, including peg-in-hole insertion.

A proceeding from 1987 elaborate on the subject of impedance control for contact-rich tasks [2]. In the proceeding, the Hogan discusses how an impedance controller can be used to avoid many of the problems that arises during a contact tasks and also eliminates computation of inverse kinematics.

A paper from 2001 presents different search strategies for peg-in-hole insertion with hole uncertainty [5]. Chhatpar and Branicky presents various blind search strategies for finding the hole, such as a method of using concentric circles as the search path, a spiral path search and a tilt search strategy. The strategies in the paper are mainly used for search areas where the uncertainty are much greater than the clearance of the hole. The main focus of the project presented in this report is peg-in-hole assembly where it is assumed that the hole uncertainty is very low. The strategies can nonetheless be useful in this case, especially spiral search which will be implemented as a step in the insertion process.

Newman et al. presented in a proceeding from 2001 the method of using sensory data in peg-in-hole assembly [6]. The paper analyses how force feedback can be mapped onto positions, especially in the case of a tilted peg since the circumstance of a peg perfectly parallel to the surface is unlikely. One conclusion of the proceeding was that mapping sensory data to a position in the 2D search space could speed up the assembly process compared to blind search if the clearance of the hole was very small.

Some of the more recent studies focus on using machine learning for peg-in-hole insertion. This has however been explored earlier. Asad explored a way of learning a desired compliance feedback for correcting a planned motion using a multi-layered neural network [7]. A more recent article from 2018 examines a method of using both touch and vision feedback data with reinforcement learning for use in peg-in-hole insertion [8].

(19)

Chapter 3

Architecture

This chapter introduces the essential architectures and system designs used for developing and running the controller. First, a high level overview of the ROS workflow is described. Then the design of the state machine running in the controller is introduced along with the the concurrency that needed to be designed. Lastly an overview of the system and how all fits together is shown. All the concepts will be explained in further details in chapter 5.

3.1

ROS (Robotics Operating System)

ROS stands for Robotics Operating System. It is a widely used framework for writing and running software on robotic systems. It allows for communication between different interfaces, nodes and controllers that run parallel to each other.

As seen in Figure 3.1, the core elements of the ROS workflow is:

• Nodes are the actual programs that are running and can be looked at as a wrapper for the node system. All computations are performed here.

• Topics are used for communication between nodes. All nodes can subscribe and publish to an arbitrary number of topics. This is done via concepts called subscribers and publishers.

• Messages are the data that is being published and received from the topics. Some more details on ROS messages can be seen in Appendix B.

(20)

Figure 3.1: A simplification of the general ROS workflow, showing how the nodes are communi-cating via messages and topics.

The blue High Level Controller is the controller that will control the robot to perform the peg-in-hole insertion. In the figure it sends messages to topics. The green robot controller node continuously reads from these topics. The robot interface sends messages to topics that explain the robot state. The high level controller then subscribes to these topics to understand the current state of the robot.

Even the high level controller itself can communicate between different internal parts using services and messages. This allows for a fluent manageable asyn-chronously programmed controller.

3.2

State Machine Design

The state machine was designed with the intention that every state reflects a movement state of the insertion process. It give each state the responsibility of executing that particular step, which makes the process clear and manageable. A simplified diagram of the state machine can be seen in Figure 3.2. Here, the essential states and transitions are shown.

(21)

3.3

Concurrency

Figure 3.3: Asynchronous execution of the main tasks in the controller.

The controller needs to read from the robot and write to the robot while at the same time execute the currently ac-tive state of the state machine. These tasks have different timing demands, the subscriber e.g. need to provide the most recent data from the robot while some states just needs execute a trajectory. This means that the tasks may need to run at different frequen-cies. To solve this, the controller was implemented to be able to execute these tasks asynchronous.

As seen in Figure 3.3, the state machine,

publisher and subscriber runs on separate threads. When the state machine is executing a state, the state has its own internal loop still on thread 1. The publisher and subscriber is not delayed by the state.

3.4

System Overview

The controller is implemented as a ROS node. A diagram of the system can be seen in Figure 3.4. The figure shows how the Insertion object acts as a wrapper for the controller. It contains a Robot object for momentarily storing the robot state, a State Machine object for handling the order of execution and a Controller object which handles all computations, this is where the majority of the work is done. The controller also contains a TrajectoryHandler for calculating trajectories, MessageHandler for handling ROS node communication by messages and Helpers for solving more general problems.

(22)
(23)

Chapter 4

Method and Tools

This chapter presents the tools and software environments used to implement the controller. Then the hardware for implementing, testing, simulating and running the peg-in-hole insertion is also presented.

4.1

Programming Languages and Libraries

ROS is adapted for developing nodes in either C++ or Python. Since the robot used for this project is shipped with a controller interface written in C++ [9], this was the language of choice.

4.1.1

C++ Libraries

The following C++ libraries were used to simplify some of the more complex tasks:

• For handling threads and synchronization of parallel execution of tasks, the Boost Tread Library [10] was used. The library provides methods for thread synchronization by using a mutex object.

• The Boost String Algorithms Library [11] was used for handling string comparison and manipulations, such as converting a string to lowercase letters. The latter was mainly used for debugging purposes when iterating the states from the command line while the controller was running.

• Handling matrices in C++ can be challenging, to make this easier, the Eigen Library [12] was used. Eigen provides various matrix datas structures with methods for manipulating them.

(24)

4.2

Tools

Listed below are the essential software and hardware used in the project. All hardware were provided by the employer AASS.

4.2.1

ROS

As described in section 3.1, ROS is the framework where the controller is running. For this project, the ROS distribution Kinetic Kame was used. ROS provides, among many other things, tools to easily debugging and logging the running application.

ROS also provides the tf library which is an essential library for handling trans-formations between frames [13].

4.2.2

Gazebo

For running the simulation in which the controller was tested, the 3D simulator Gazebo[14] was used. Gazebo is used to simulate the robot in a provided

environ-ment. A gazebo ROS package [15] was also used which functions as a wrapper for running Gazebo in ROS.

4.2.3

rviz

For visualizing the robot in simulation and also when running the controller on the real robot, the ROS package rviz [16] was used which is a 3D visualizer used for the ROS framework.

4.2.4

The Robot

The robot used in this project is the Franka Emika Panda. The robot is a 7 degrees of freedom robotic arm provided with torque sensors in all seven axes and have a repeatability of +/- 0.1 mm, (see Appendix Appendix A).

(25)

4.2.5

Other Applications Used for Development

The following applications were used when developing the controller:

• All development was done on the Linux operating system with distribution Ubuntu 16.04.6 LTS [17]

• Text editors used for code development was Vim [18] and Visual Studio Code [19].

• Plotting and verifying trajectories before testing was done using MATLAB [20].

(26)
(27)

Chapter 5

Implementation

This chapter describes how each of the major parts of the project was implemented. The first section shows how the controller was implemented as a ROS node by first presenting a high level overview of the node and then go into details in the subsections. The next section describes the the state machine, details on the most important states and how each of the individual problem of the controller was solved. The last two sections describes how the controller was developed to run in simulation and on the real robot.

5.1

ROS Node

As described in section 3.1, a ROS node is used for running independent programs in the ROS environment. The node running the controller was implemented in a way proposed by Yu Zhang [21]. The tasks and behavior of the node is split up as shown in Figure 5.1. The elements of the node can be described as follows:

• The constructor is used for passing data to the controller that needs to be initialized before the actual node class is instantiated.

• The purpose of init is to connect and create important parts of the class, such as publishers and subscribers.

• The state machine will be running in the timer callback method and the subscriber callback method is used for reading the robot state.

(28)

Figure 5.1: High level description of the ROS node.

5.1.1

Timers and Asynchronous Execution of the State

Ma-chine

The state machine is running concurrent to the rest of the controller. In ROS this can be achieved with the use of a timer callback function. The function is scheduled for callback at a frequency of 10 Hz. It was considered that 10 Hz would make the robot sufficiently responsive to the environment and to execute trajectories. All publishers and subscribers running in the controller is also running parallel on separate threads. The publishers and subscribers are writing and reading the robot state and are therefore called at rate of 100 Hz to always keep the robot object updated with the most recent actual robot state with a low delay.

Figure 5.2 is showing an example of a timer callback that is calling a state. In the middle of the state running, a publisher is writing new data to the robot object. The state is then reading the new robot state.

(29)

Figure 5.2: Sequence diagram showing parallel execution of a state concurrent with a publisher callback writing to the robot object.

5.1.2

Publishers and Subscribers

As seen in Figure 5.3, the insertion node is publishing a joint trajectory to the joint trajectory controller that is used for controlling the robot in joint space. The node is also publishing a pose and stiffness in Cartesian space for the robot tooltip.

(30)

In the same way, the insertion node is subscribing to topics to receive information about the robot state. Figure 5.4 shows the node subscribing to the topics tf (see section 4.2.1) and external force for reading the forces acting upon the tooltip.

Figure 5.4: Insertion node subscribing to topics that the robot node is publishing to.

5.1.3

Messages

Below is a list of the messages used in this project. The list shows the names along with the data structure of the messages when subscribing and publishing to ROS topics. All messages also have a Header field, not shown in the list,

which holds metadata about the message. The namespaces trajectory_msgsand geometry_msgs are common message types provided by ROS. More details on ROS

messages are provided in Appendix B.

• trajectory_msgs/JointTrajectory, used for publishing joint space

trajec-tories. The message contains a list of the joint names and a list of points in joint space making up the trajectory.

string[] joint_names

JointTrajectoryPoint[] points

• geometry_msgs/Pose was used for publishing a desired 3D pose for the robot

and reading the current robot pose. The messages contains both a point in Cartesion space and an orientation represented as a Quaternion.

Point position Quaternion orientation

(31)

Vector3 linear Vector3 angular

• geometry_msgs/Wrench, used for reading the forces that was acted upon the

robot. The messages splits the force up in its linear (force) and angular (torque) parts.

Vector3 force Vector3 torque

5.2

State Machine

In section 3.2, the high level idea of the state machine was presented. This section will describe four of the most essential states of the state machine and how the transition to the succeeding state was implemented.

Figure 5.5 is showing the insertion process based on the state machine.

(32)

Which of the state that needs to be executed is decided by the state machine. Since the state machine is fairly simple – it is designed to execute in a chronological order – it was implemented as a basic C++ switch. Listing 1 shows the basic concept of the state machine. The switch is checking the activeState, the occurring switch

case then calls the matching function which performs the computations.

Separating the state machine from the parts of the controller which performs computations gives more flexibility. The states can run at different frequencies than other parts of the controller node. As described in subsection 5.1.1, the subscribers and publishers is running at 100 Hz to be able to read and update the robot with minimum delay. The states of the state machine is running at 10 Hz enum State { Start, MoveToInitialPosition, ExternalDownMovement, SpiralMotion, InternalDownMovement, InsertionWiggle, Finish, Idle }; switch(activeState) {

case Start: { start(); break; }

case MoveToInitialPosition: { moveToInitialPosition(); break;}

case ExternalDownMovement: { externalDownMovement();break; } ... } void start() { controller.startState(); activeState = MoveToInitialPosition; } void moveToInitialPosition() { controller.moveToInitialPositionState(); activeState = ExternalDownMovement; } ...

Listing 1: State machine implementation as a basic switch.

5.2.1

Move to Initial Position

(33)

Moving the robot in any position using the impedance controller is done simply by publishing a trajectory of set points to the controller. An evenly distributed trajectory of points was calculated by simply dividing the difference in a starting point Pstart and goal point Pgoal with the number of desired points in the trajectory

N, as seen in Equation 5.1.

Pstep =

Pstart− Pgoal

N (5.1)

The point Pn = Pstart + nPstep where 0 6 n 6 N is then added to a vector,

implementation of this shown below in Listing 2.

...

Trajectory initialPositionTrajectory; Point pointStep;

pointStep.x = (goalPoint.x - startPoint.x) / nrOfPoints; pointStep.y = (goalPoint.y - startPoint.y) / nrOfPoints; pointStep.z = (goalPoint.z - startPoint.z) / nrOfPoints;

for (auto n = 0; i <= nrOfPoints; n++) {

Point point;

point.x = startPoint.x + (n * pointStep.x); point.y = startPoint.y + (n * pointStep.y); point.z = startPoint.z + (n * pointStep.z); initialPositionTrajectory.push_back(point); }

...

Listing 2: Generatinging a linear trajectory.

The goal point Pgoal was found by inserting the robot tool into the hole by hand

and recording the x, y and z-coordinate of the tooltip, increasing of course the z-value to get the desired 5 cm above the hole.

A transition to the next state is executed as soon as the last point in the trajectory has been published to the impedance controller.

5.2.2

Downward Movement

Moving the peg down is done in the same way described in the previous section. But since the peg should be aligned right above the hole, the x- and y-coordinates are static.

(34)

move on to the next state. This is done by, as before, continuously publishing a trajectory of points to the controller. Between each publication, check if the tool tip touches the floor by reading the force in z-axis with a floorContact()checker.

If the force is greater than a set maximum value, the state machine iterates to the next state.

Figure 5.6 shows a graph of the forces that is acted upon the tool tip of the robot in each of the x, y and z-axes. The cyan colored line represents the force in the z-axis. A spike can be seen between time 21.0 s and 21.5 s which indicates that the peg has made contact with the floor.

Figure 5.6: Forces acted upon the x, y and z-axes of the robots tool tip at an instance when the peg is making contact with the floor.

The noise in the z-axis during a downward motion was observed to be between 0 - 1 N. The maximum force before stopping was set to 1.3 N. The compliance of the robot is preserving a desired downward force to the goal z-coordinate after the trajectory has stopped being published, as seen in Figure 5.6. Due to the fact that the floorContact()check is reading the forces at a rate of 10 Hz, the force is

making its way up to 3 N before stopping. This is however not a problem as long as the force is not generating more friction than the motions in the succeeding states can overcome.

(35)

5.2.3

Spiral Motion

The purpose of this state is to cover a large area in the search space while at the same time execute a smooth motion. This can be done in several ways but for this task, a spiral motion was chosen, more specifically, an Archimedean spiral. The Archimedean spiral has a constant distance between each "turn" and can be described by its polar coordinates with the following equation:

r = a + bθ (5.2)

where a describes how far away from the origin the spiral should start and b represents the distance between each turn of the spiral. The equation can be represented in the Cartesian coordinate system by the x- and y-coordinate [22] as the following equations:

x = rcos(θ) y = rsin(θ)

Part of the function that generates the spiral can be seen below in Listing 3.

Trajectory generateArchimedeanSpiral(doublea, doubleb,int nrOfPoints, int rotations) {

...

for (doublen = 0.0; n <= nrOfPoints; n += 1.0) {

Point point;

doubletheta = sqrt(n / nrOfPoints) * (rotations * 2* M_PI);

doubler = (a - b * theta);

point.x = startPoint.x + r * cos(theta); point.y = startPoint.y + r * sin(theta); point.z = startPoint.z; spiral.push_back(point); } ... returnspiral; }

(36)

Since the trajectory needs to be a number of set points, a discretization of the spiral was implemented by a loop where each iteration of the loop had the following angle:

θ =r n

NΩ2π (5.3)

where n is the current iteration of the loop, N is the number of desired points in the trajectory and Ω decides how many turns the spiral should make, . The factor p

n/N is "stepping" through the spiral, increasing the angle as n is increasing.

Taking the square root of n/N increases the function steeper in the beginning of

the spiral; thus, a high frequency of set points in the smaller inner rotations can be avoided. This is not however distributing the points at an exact interval, but it is a good enough approximation. The reason for spacing the points evenly throughout the trajectory is to avoid an increasing velocity at the outer rotations of the spiral when the impedance controller is following the trajectory.

A sample output of two trajectories generated by the function

generateArchimedeanSpiral(a, b, N, rotations) with the parameters

a = 0.0, b = 0.0005, N = 150, rotations = 6

can be seen plotted in Figure 5.7. The images shows a comparison between the unevenly spaced points with stepping factor n/N in Figure 5.7(a) and the evenly

spaced points with the stepping factor pn/N in Figure 5.7(b).

(a) Unevenly spaced points (b) Evenly spaced points Figure 5.7: Plotting of spiral trajectories with and without evenly spaced points.

(37)

5.2.4

Wiggle

Since the clearance between the peg and the hole is very tight, straightening the end effector of the robot would not be enough to prevent jamming. The compliance of the robot can be used. Since there is a constant downward force, as described in section 5.2.3, tilting the peg in any axis could release the jamming for a brief time. Repeating this step could hopefully lead to a complete insertion.

Rotating the tool tip for the purpose of prevent jamming is not done in the same way as moving the tool tip in a predefined trajectory. The x, y and z-coordinates needs to be static while the orientation has to be manipulated based on the forces recorded on the peg.

The impedance controller used for the robot represents orientation in quaternions. Quaternions have some computational advantages over rotational matrices [23], it can however be somewhat unintuitive to work with. For this reason, the rotation was done by:

1. converting the Quaternion to a homogeneous transformation matrix, 2. rotating the transformation matrix with Euler angles and

3. converting the rotated transformation matrix back to Quaternions.

The subscriber is fetching the robot state and storing the data in a panda object.

The robot state can therefore be read from the object as a Pose data type.

Converting from a Posedata type to a transformation matrix can be done with

the poseMsgToEigen() from the tf library. The function returns a data type Transform from the Eigen library.

Rotating the transformation matrix can be done by using rotation matrices around the principle axes x, y and z with the Euler angles α, β and γ [24]:

(38)

Rx(α) =      1 0 0 0 0 cos α − sin α 0 0 sin α cos α 0 0 0 0 1      Ry(β) =      cos β 0 sin β 0 0 1 0 0 − sin β 0 cos β 0 0 0 0 1      Rz(γ) =      cos γ − sin γ 0 0 sin γ cos γ 0 0 0 0 1 0 0 0 0 1     

The new rotation matrix R0

4×4 can be composed of the following multiplication

[25]:

R0 = Rx(α)Ry(β)Rz(γ)

The transformation matrix T4×4converted from poseMsgToEigen() can be rotated

by the multiplication:

T0 = T R0

and lastly converted back to a Pose data type using the corresponding function poseEigenToMsg() which can then be published to the impedance controller. The

conversion between the Posemessage and the transformation matrices can be seen

in Listing 4. // Convert to matrix Eigen::Affine3d tMatrix; tf::poseMsgToEigen(message.pose, tMatrix); // Perform rotation // Convert back to msg tf::poseEigenToMsg(rotated_tMatrix, message.pose);

(39)

5.3

Controlling the Robot

Developing the controller was done by first simulation to get the basic movements of the state machine working. Development was then moved to the real robot. This section will first describe how developing in simulation was done. Then the process of porting the code will be specified. And finally some details on working with the robot and handling the force interpretation will be presented.

5.3.1

Simulation

The basic movements of the state machine was developed and tested in simulation to make the process safer and faster. One purpose of working in simulation before actually controlling the real robot is to test the controller and see how the robot is behaving. It is however not certain that the behaviour of the real robot will be the same as in simulation.

The state machine was build in an iterative order. The quality of each state could be established in rviz which shows the simulated motion on a 3D model, as seen in Figure 5.8.

(40)

No force feedback control or interpretation was handled in simulations. Since the forces acting on the tool tip is very small, it would not be reasonable to assume that the forces would translate to the real robot since it is hard to model this in simulation. Therefore, only the motions was developed in simulations. As soon as the force-based state transitions was to be implemented the development was shifted to the real robot.

5.3.2

Working on the Robot

The first thing to do in getting the controller to run on the actual robot was to port the code from the ROS environment running the simulation to the real environment. This process was fairly simple and consisted mostly of parameterising some variables that differs in simulation and reality. The impedance controller running in simulation was not built for running on the real robot, so the majority of the variables needed to be parameterized were variables that differed in the impedance controllers, such as stiffness and damping.

When the code was ported the work consisted of testing all the steps of the state machine. Testing the state machine was mainly about tuning some parameters for getting the robot to perform the movements with sufficient precision.

Tuning the Parameters

The significant parameters to tune for getting desired robot behavior was: • The stiffness and damping for the impedance controller. Both the parameters

could be tuned in translational xydirection and rotational x, y and z-direction, which gives 12 parameters to tune.

• The number of set points in the trajectories the impedance controller was following.

Setting the stiffness low gives the impedance controller makes the tool tip more compliant which helps with guiding the tool. It also makes the execution of the trajectories somewhat smoother. The downside of a low stiffness is poor precision of the tool tip. The damping prevents oscillation of the tool tip and needed tuning only when the robot was making vigorous movements. Tuning the damping could also be in combination with trying different quantities of set points.

(41)

Chapter 6

Result

This chapter will bring about the result of the sufficient solution. It will show the results of a test performed to show the current solutions success rate as well as an explanation for how well each state in the state machine currently performs.

6.1

The Sufficient Solution

The controller is able to perform a full peg-in-hole insertion. It can automatically go through all the states from an arbitrary start position all the way to a full peg-in-hole insertion.

6.1.1

Test Runs

A repeating insertion process was executed 21 times to test the functionality of the controller. The test was performed by executing the program in successions one after the other. The tool was pulled out and put in a spot to the side and above the hole so that it could move to the initial position in a mostly similar way upon each test.

The time was stopped when the insertion came to a full insertion, when it failed or when the state machine ended. An insertions is accomplished when the peg inserted the peg in the hole, a full insertions is performed when the peg is inserted all the way to the bottom of the template. The result of the test runs can be seen in Table 6.1.

(42)

Table 6.1: Result of 21 insertion attempts.

Run Time (s) Insertion Full Insertion Failing State

1 32 X - Spiral 2 49 X X -3 49 X X -4 49 X X -5 49 X X -6 43 X X -7 28 X - Spiral 8 49 X X Wiggle 9 49 X X Wiggle 10 49 X X Wiggle 11 49 X X Wiggle 12 27 X - Spiral 13 49 X X Wiggle 14 49 X X Wiggle 15 29 X - Spiral 16 28 X - Spiral 17 28 X - Spiral 18 49 X X Wiggle 19 49 X X Wiggle 20 28 X - Spiral 21 49 X X Wiggle

The following presumption can be made from the performed tests:

• The time from starting the controller to full insertions is 49 seconds. • The controller is performing an insertion 66 % of the times.

• The controller is performing a full insertion 24 % of the times.

It should to be noted that the statistics in the previous list are not exact since 21 tests is not sufficient for making a presumption that reflects reality.

(43)

6.1.2

State Machine

The steps of one of the test runs can be seen below in Figure 6.1.

(a) Move to initial position (b) Downward movement

(c) Spiral motion making contact with the hole

(d) Insertion wiggle

Figure 6.1: Test run of the insertion process.

The following steps are shown in the image:

• Figure 6.1(a) shows the movement to the initial position 5 cm above the hole.

(44)

• In Figure 6.1(b) the robot is performing the downward movement towards the hole. The tool is moving down in a straight line and stops as soon as the tool tip touches the template.

• The spiral motion is performed in Figure 6.1(c). The spiral trajectory is followed smoothly and finds the hole within 2 seconds with the current hole error.

• Finally the insertion wiggle state is shown in Figure 6.1(d). The motion is able to prevent jamming and moves the peg down the hole.

Moving to the initial position using the Cartesian impedance controller works well. The only flaw is a slight variance in the end position after completed trajectory, however this is likely due to the stiffness parameters of the impedance controller and can be tuned.

The downward movement step also works as intended. The only improvements could be to move faster by having less steps in the trajectory. The stiffness parameters could also be tuned to make it more accurate.

The spiral motion is where the current implementation is limited. The spiral motion works 14 times out of 21 (66 %) according to a trail run of 21 tests. There is much room for improvement for this controller and a reiteration of the external force reading is one of them. In this case, the detection to determine whether the tool is touching the surface of the plate or is inside the hole has an insufficient success rate. At times the controller is signaling a false positive hole detection. The threshold and needs to be updated to detect this clearer to increase the overall success rate.

Finally, the insertion wiggle has much room for improvement. As of now, it can do a full completion 5 times out of 21 (23 %) based on the test runs. It is very rough as of now. The motion simply alternates between two given orientations in a wiggle while pushing down until the peg is in the hole. While reliable and gives result, it is flawed. It doesn’t wiggle to a direction that would have the most likelihood of making the downward movement smoother. It doesn’t read the current external force that is being exerted unto the tool. This reading is crucial to make some sensible movements to allow the robot to move in reactionary way to where it is in the hole. However this solution is an anti-jamming solution, which would fall into the improvement phase. The current iteration completes the sufficient solution.

(45)

6.1.3

Limitations

The controller has some limitations as of the current implementation, the most notable are:

• The external force reading in general is limited. As of now, the controller detects floor contact and hole contact. This can be expanded further. • The solution is currently coded to the one chamfered hole. It is possible and

not particularly demanding to make the controller able to run through the insertion unto other holes, it would require some changes of coordinates and a minor update of the code to be more compatible with this feature. • A full insertion process takes 49 seconds. This can be improved by publishing

fewer set points in the trajectories. It has to be tuned to retain accuracy. As can be told from the test run, the solution deteriorates in success upon multiple successive iterations. The biggest reason for this is probably due to the nature of the wiggle. The wiggle is not as soft as it could be, as it should move as little as possible in the most apt direction. Knowing what this direction is however would require a good read on the external force. Currently, it doesn’t read at all, so it does the next best thing and dramatically moves about two orientation while pushing down until it gets in. It can be assumed this is an effect on the tool, as it is not attached to the robot too firm, so the repeated wiggles could perhaps effect its attachment slightly.

The controller has much room for improvement. It has as stated a success rate of 14 out of 21 (66 %). However it only managed to enter fully 5 times out of the 14 successes (36 %). The wiggle has the most room for improvement out of the current steps.

(46)
(47)

Chapter 7

Discussion

This chapter will cover a discussion regarding the results and it’s implications. This is done by discussing the results in comparison to the requirements, going through the social and financial implications of the project and finally discussing potential future work and improvements that could be done for the project.

7.1

Requirements

One way to asses whether the project succeeded at what it set out to do is to compare the results to the initial requirements and compare the difference. That is what this subsection will cover. It will begin with the primary requirements and then compare the secondary requirements.

7.1.1

Primary

The requirements for this project were the following:

• perform tool insertion with no added uncertainty to the hole center, • have an insertion success rate of about 50 % and

• not let its time of the insertion process take longer than three minutes. The solution as of now can complete all of the primary requirements. The robot can perform peg-in-hole insertion with no added uncertainty. It had a success rate of above 50 %, it was in fact 66 %. The insertion process was much shorter than three minutes, a full insertion never took longer than 49 seconds.

This does not mean however that there is no room for improvement. The solution can be made faster in a couple of steps. For instance, the wiggle is as of the current implementation not particularly clever. It merely wiggles back and forth between two positions. This can be vastly improved with a force reading to determine

(48)

The process can have slight improvements in speed by making the trajectories consist of less points. As of now, the robot is given very lenient times and amount of points for its movements from the start position to the surface of the hole. These can all be shortened to make the initial movements much faster. To offset a potential inaccuracy due to this fast movement, the trajectories can be divided to move faster the further it is from the hole and move slower and more accurate the closer the tool gets to the hole. That way the speed would be increased while still maintaining the crucial accuracy that is needed to consistently land close to the hole.

Given these improvements it is not unlikely to assume the process can be reduced to an insertion taking no longer than 30 seconds. It could perhaps even go lower. It would come down to the classic issue of speed vs accuracy, which would be impossible to determine here as it would have to be determined depending on the desired requirements a particular insertion would value.

7.1.2

Secondary

The secondary requirements were the following:

• Develop an understanding and solve the problem of the peg getting jammed in the hole.

• Test the controller with different uncertainties of hole position. • Test the solution on both chamfered and chamferless holes.

• To have the implemented states functional with appropriate reset or fail states for each of the states.

None of these have been implemented as of now. However it would not require much time to complete these.

The jamming problem largely occurs because of the current iteration of the wiggle state. As mentioned previously, it does not take into consideration the force reading. Should it do so, the jamming could be prevented through the controller.

The different uncertainties would be likely to succeed. All it would require to be tested is a change of coordinates of the starting coordinates. It would have to be tested in two ways; one way to simply move it further from the hole, the other

(49)

outwards until it ceases to feel contact with the floor, i.e. when it is in the hole. Different uncertainties should be possible for the current implementation, however the requirement is not succeeded due to this having not been tested yet.

Looking at the results from another perspective however, the results are very prominent. One of the initial questions for this project was "can it be done?" Is this peg in hole process automatable? It had been tested before and not succeeded due to the lack of compliance in the insertion. However even with a compliance controller with improvement potential, it still manages to succeed the task with a repeatable success rate, which was the original intent of the project.

One has to separate whether or not it was about proving it could be done or if it could be done repeatedly. The project at hand was about the primary requirements. Improving the success rate would be very welcome, however how this solution will be implemented in a real industrial robot might be quite different. In fact, this solution would only be used as inspiration for a new controller that is built from scratch to suit the environment it will be used in. In that case, improving the current implementation may not be of essence. The most important part was to show it could be done.

7.2

Social and Financial Implications

What are the implications of automating this type of work? A common thought is that labor should be replaced by automation, as it is created with the intent of being a substitute for it. However, this does not necessarily make human labor less relevant or interesting. According to a study from 2015 it actually increases and complements human labor [26]. It is likely that when fully used, this insertion controller could do the same and have a positive effect on the interest of human labor.

7.3

Further Work

The improvements that can be done to this project are numerous. The first and most obvious is to expand the controller with a method to find the coordinates for the initial position above the hole. As of now, this coordinate is provided through testing and the controller itself has no means of finding it. This could be done through a camera and using digital image processing to determine the

(50)

This would be necessary to further automate the process. Because as of now, the entire move set of the controller is entirely based upon the correct coordi-nates. If these were provided, the controller could complete perform the insertion process.

The further improvement that can be done are as mentioned previously, to use a force reading in the wiggle state.

One addition possible for future work is the development and implementation of a HMI (Human Machine Interface). A HMI would be necessary for the controller in order to provide relevant information about the current state and condition of the controller as well as allowing control to the user. This could be for instance choosing which holes to perform an insertion unto or providing the coordinates for a given hole.

(51)

Chapter 8

Reflection

This chapter will cover a reflection of what was learned from the project and its work process. It will cover what knowledges were acquired, what skills were developed and finally a reflection on the evaluating the result of a project.

8.1

Skills and Abilities

The project assumed an existing knowledge regarding computer science and robotics in order to realistically be able to complete the project. However as any worthwhile project would garnish a further developed skill-set at the end of it. The primary skills learned during this project was working with ROS and working with hardware.

8.1.1

ROS

Due to this project, a greater understanding for ROS was developed. Initially, only a basic understanding from a set of tutorials had been done to understand ROS. After the project, a bit of an intuition for the system had been developed and working with ROS in future projects would be welcoming.

8.1.2

Working with Hardware

Working with the hardware was challenging. This was largely due to the lack of experience. One of the problems that occurred was that an incorrect version of the impedance controller designed for the simulator had been initially used on the robot. The controller was not compatible with the robot interface and caused the robot to not obey commands in the same way as it did in the simulation. It was difficult to determine the cause of said movement and it set back the project by a week in an attempt to debug the robot. In the end it turned out fine and served as a lesson of the importance of experience in order to save time in a project.

(52)

8.2

Knowledge and Understanding

Apart from the knowledges related to the technology used to solve the given problem, certain meta lessons were taught during this project as well. There were two specific concepts that became apparent and more well understood in this project. One was the challenge and importance of finding and reading relevant scientific papers and articles. The other was the intuitive difficult of assessing the success of ones result.

8.2.1

Scientific Papers

This project taught the simpleness of finding relevant papers but the difficulty of reading, interpretation and using them. Find relevant papers is easy, keywords and common references make it relatively easy to find what one is looking for. However using them requires practice and experience. A basic lesson taught during this project was to read the abstract and headlines first before going in depth into the article. Afterwards, one can read through parts of the text. Upon the third reading, one can try to understand the more complicated parts of the article. Learning this made the daunting and complicated papers seem much more readable and useful.

8.3

Evaluation Ability and Approach

A lesson taught during this project was the importance of using the initial require-ments as a baseline to judge the result. Every project and solution could probably be improved. Nothing is perfect and there is always room for improvement. A solution is not failed because it could have been better. It is a success if it meets the demands set out for it initially. Even though intuitively, the current solution has room for improvement, it serves its purpose. Being able to understand this allows one to evaluate success in a more predictable manner in a way possible before the project is even begun. This also allows for a more professional attitude to the products quality. It met the goals that were set initially, then it is a success, no matter what could be improved. If the product is still flawed then the problem were the initial requirements, not the result.

(53)

Bibliography

[1] Olsson K, Larsson A. Automated drilling with collaborative robots [Bachelor’s Thesis]; 2017.

[2] Hogan N. Impedance control: An approach to manipulation: Part

II—Implementation. Journal of dynamic systems, measurement, and control. 1985;107(1):8–16.

[3] Song P, Yu Y, Zhang X. Impedance Control of Robots: An Overview. In: 2017 2nd International Conference on Cybernetics, Robotics and Control (CRC); 2017. p. 51–55.

[4] Whitney DE. Historical perspective and state of the art in robot force control. The International Journal of Robotics Research. 1987;6(1):3–14.

[5] Chhatpar SR, Branicky MS. Search strategies for peg-in-hole assemblies with position uncertainty. In: Proceedings 2001 IEEE/RSJ International Conference on Intelligent Robots and Systems. Expanding the Societal Role of Robotics in the the Next Millennium (Cat. No. 01CH37180). vol. 3. IEEE; 2001. p. 1465–1470.

[6] Newman WS, Zhao Y, Pao YH. Interpretation of force and moment signals for compliant peg-in-hole assembly. In: Proceedings 2001 ICRA. IEEE International Conference on Robotics and Automation (Cat. No. 01CH37164). vol. 1. IEEE; 2001. p. 571–576.

[7] Asada H. Teaching and learning of compliance using neural nets: Repre-sentation and generation of nonlinear compliance. In: Proceedings., IEEE International Conference on Robotics and Automation. IEEE; 1990. p. 1237– 1244.

[8] Lee MA, Zhu Y, Srinivasan K, Shah P, Savarese S, Fei-Fei L, et al. Making Sense of Vision and Touch: Self-Supervised Learning of Multimodal Represen-tations for Contact-Rich Tasks. arXiv e-prints. 2018 Oct;p. arXiv:1810.10191. [9] GmbH FE. Franka Control Interface Documentation;. Accessed: 2019-05-27.

(54)

Available from: https://www.boost.org/doc/libs/1_70_0/doc/html/thread. html.

[11] Droba P. Boost String Algorithms Library;. Accessed:

2019-05-27. Available from: https://www.boost.org/doc/libs/1_60_0/doc/html/

string_algo.html.

[12] Guennebaud G, Jacob B, et al.. Eigen v3; 2010. Accessed: 2019-05-27. http://eigen.tuxfamily.org.

[13] Foote T. tf: The transform library. In: Technologies for Practical Robot Applications (TePRA), 2013 IEEE International Conference on. Open-Source Software workshop; 2013. p. 1–6.

[14] Koenig N, Hsu J. Gazebo Homepage;. Accessed: 2019-06-9. Available from:

http://gazebosim.org/.

[15] Koenig N, Howard A. gazebo ROS Package;. Accessed: 2019-06-09. Available from: http://wiki.ros.org/gazebo.

[16] Hershberger D, Gossow D, Faust J. rviz ROS Package;. Accessed: 2019-05-27. Available from: http://wiki.ros.org/rviz.

[17] Ubuntu Xenial Xerus Release Notes;. Accessed: 2019-05-27. Available from:

https://wiki.ubuntu.com/XenialXerus/ReleaseNotes.

[18] Vim Website;. Accessed: 2019-05-27. Available from: https://www.vim.org/.

[19] Visual Studio Code Website;. Accessed: 2019-05-27. Available from: https: //code.visualstudio.com/.

[20] MATLAB. version 9.5.0 (R2018b). Natick, Massachusetts: The MathWorks Inc.; 2010.

[21] Zhang Y. Several Ways of Writing a ROS Node;. Accessed:

2019-05-23. Available from: https://yuzhangbit.github.io/tools/

several-ways-of-writing-a-ros-node/.

[22] Vyshenska K. How to Build a Parameterized Archimedean Spiral Geome-try;. Accessed: 2019-05-26. Available from: https://www.comsol.com/blogs/ how-to-build-a-parameterized-archimedean-spiral-geometry.

(55)

[24] Slabaugh GG. Computing Euler angles from a rotation matrix. Retrieved on August. 1999;6(2000):39–63.

[25] Diebel J. Representing attitude: Euler angles, unit quaternions, and rotation vectors. Matrix. 2006;58(15-16):1–35.

[26] Autor DH. Why Are There Still So Many Jobs? The History and Fu-ture of Workplace Automation. Journal of Economic Perspectives. 2015 September;29(3):3–30.

[27] Kim YL, Song HC, Song JB. Hole detection algorithm for chamferless square peg-in-hole based on shape recognition using F/T sensor. International Journal of Precision Engineering and Manufacturing. 2014 Mar;15(3):425– 432.

[28] ROS msg wiki;. Accessed: 2019-06-11. Available from: http://wiki.ros.

org/msg.

[29] ROS catkin wiki;. Accessed: 2019-06-18. Available from: http://wiki.ros. org/catkin.

(56)
(57)

Panda

TECHNICAL DATA 1, 2

interfaces ▪ Ethernet (TCP/IP) for visual intuitive programming with Desk

▪ input for external enabling device

▪ input for external activation device or a safeguard ▪ Control connector ▪ Hand connector interaction enabling and guiding button,

selection of guiding mode, Pilot user interface

mounting flange DIN ISO 9409-1-A50 installation position upright

weight ~ 18 kg

protection rating IP30 ambient

temperature

▪ +15°C to 25°C (typical) ▪ +5°C to + 45°C (extended) 3 air humidity 20% to 80% non-condensing Control

interfaces ▪ Ethernet (TCP/IP) for Internet and/or shop-floor connection ▪ power connector IEC

60320-C14 (V-Lock) ▪ Arm connector

controller size (19”) 355 x 483 x 89 mm (D x W x H) supply voltage 100 VAC - 240 VAC

mains frequency 47- 63 Hz power consumption ▪ max. 600 W

▪ average ~ 300 W active power factor

correction (PFC) yes

weight ~ 7 kg

protection rating IP20 ambient

temperature

▪ +15°C to 25°C (typical) ▪ +5°C to + 45°C (extended) 3 air humidity 20% to 80% non-condensing

Hand

parallel gripper with exchangeable fingers grasping force continuous force: 70 N

maximum force: 140 N travel (travel speed) 80 mm (50 mm/s per finger) weight ~ 0.7 kg

Desk

platform via modern web browser programming visual & intuitive, dialog-based Apps can be composed into complex

workflows to create Tasks and Solutions

CE out of the box solutions

Check www.franka.deto see if for your application a CE out of the box solution is available already. If so, you only have to go through an enclosed CE-checklist and you can start using Panda out of the box without performing an additional risk analysis.

1 technical data is subject to change

2 if you have not purchased a Panda - CE out of the

box solution, or don’t comply with the CE-checklist the operator is responsible for the performance of a risk analysis and safe operation of the robot in accordance to its intended use and applicable standards and laws. 3 performance can be reduced when operating outside the

typical temperature range

Arm

degrees of freedom 7 DOF

payload 3 kg

sensitivity torque sensors in all 7 axes maximum reach 855 mm

joint position limits [°]

A1: -166/166, A2: -101/101, A3: -166/166, A4: -176/-4, A5: -166/166, A6: -1/215, A7: -166/166

joint velocity limits [°/s]

A1: 150, A2: 150, A3: 150, A4: 150, A5: 180, A6: 180, A7: 180 Cartesian velocity

limits

Up to 2 m/s end effector speed repeatability +/- 0.1 mm (ISO 9283)

Appendix A

Franka Emika Panda Datasheet

(58)
(59)

Appendix B

ROS Messages

ROS messages are used for passing data from one ROS node to another. Nodes can publish messages to a ROS topic, all other nodes in the workspace can then subscribe to the topic and receiv the message.

Messages are of type .msg which is a ROS description file for handling data as

messages. The .msgfile consists of fields with the data types that the message

should handle. [28]. An example of this would be a message file Coordinate.msg

that could look like Listing 5.

float64 x float64 y float64 z

Listing 5: Example ROS message file Coordinate.msg

The .msgfiles are then converted into either C++ or Python code (whatever is

used in the ROS node) with the ROS build tool catkin [29] so that it can be used for computation (Listing 6).

#include "Coordinate.h" ... Coordinate coordinate; coordinate.x =2.0; coordinate.y =4.0; coordinate.z =0.0; publisher.publish(coordinate);

References

Related documents

För att uppskatta den totala effekten av reformerna måste dock hänsyn tas till såväl samt- liga priseffekter som sammansättningseffekter, till följd av ökad försäljningsandel

The increasing availability of data and attention to services has increased the understanding of the contribution of services to innovation and productivity in

Av tabellen framgår att det behövs utförlig information om de projekt som genomförs vid instituten. Då Tillväxtanalys ska föreslå en metod som kan visa hur institutens verksamhet

Närmare 90 procent av de statliga medlen (intäkter och utgifter) för näringslivets klimatomställning går till generella styrmedel, det vill säga styrmedel som påverkar

• Utbildningsnivåerna i Sveriges FA-regioner varierar kraftigt. I Stockholm har 46 procent av de sysselsatta eftergymnasial utbildning, medan samma andel i Dorotea endast

I dag uppgår denna del av befolkningen till knappt 4 200 personer och år 2030 beräknas det finnas drygt 4 800 personer i Gällivare kommun som är 65 år eller äldre i

Den förbättrade tillgängligheten berör framför allt boende i områden med en mycket hög eller hög tillgänglighet till tätorter, men även antalet personer med längre än

På många små orter i gles- och landsbygder, där varken några nya apotek eller försälj- ningsställen för receptfria läkemedel har tillkommit, är nätet av