Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Gcode class #48

Merged
merged 39 commits into from
Jul 19, 2023
Merged

Gcode class #48

merged 39 commits into from
Jul 19, 2023

Conversation

philipp1604
Copy link
Collaborator

Description

The Gcode Class is able to read G-Code from a textfile and to run it on the simulation. With the G-Code Class a demonstration file was implemented which runs two different G-Codes from the example folder. The basic G-Commands were implemented directly in the Class. M-Commands and T-Commands can be defined externally with lambda calls.

Motivation and Context

In order to test G-Code on the simulation an appropriate interface was necessary.

How has this been tested?

A test class was created which tests all the implemented functions separately. For the read-method different test commands were created and the output was checked. For the run-method different test points and test commands were compared to the position of the endeffector or tool.

Types of changes

  • Bug fix (non-breaking change which fixes an issue)
  • New feature (non-breaking change which adds functionality)
  • Breaking change (fix or feature that would cause existing functionality to not work as expected)

Checklist:

  • My code follows the code style of this project.
  • My change requires a change to the documentation.
  • I have updated the documentation accordingly.

This is the work for the Gcode_class which as been done before joining the Github project
New:
- new loops in order to ensure correct positioning for the interpolations and G0
- Examples for G0 and G1/2/3
- Gcode_dem that gives a demonstration of how the gcode class can be implemented

TO DO's
- adjusting the style of the code (according PEP8)
- finnishing the test_gcode_class
This is a final comit before merging into main.
@philipp1604 philipp1604 added the enhancement New feature or request label Mar 24, 2023
@philipp1604 philipp1604 self-assigned this Mar 24, 2023
@codecov
Copy link

codecov bot commented Mar 24, 2023

Codecov Report

Merging #48 (326e5f2) into main (4cf818b) will increase coverage by 3.15%.
The diff coverage is 98.87%.

@@            Coverage Diff             @@
##             main      #48      +/-   ##
==========================================
+ Coverage   83.51%   86.66%   +3.15%     
==========================================
  Files          14       15       +1     
  Lines         752      930     +178     
==========================================
+ Hits          628      806     +178     
  Misses        124      124              
Impacted Files Coverage Δ
src/pybullet_industrial/g_code_processor.py 98.87% <98.87%> (ø)
src/pybullet_industrial/__init__.py 100.00% <100.00%> (ø)

... and 1 file with indirect coverage changes

- Minor Codiga Errors were adjusted
"""
e = self.active_endeffector

for positions, orientations, tool_path in path:
Copy link
Collaborator Author

Choose a reason for hiding this comment

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

tool_path is can't be skipped

Copy link
Member

Choose a reason for hiding this comment

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

that is true but if a variable is not accessed it should be declared using "_" in this example:
for positions, orientations, _ in path:

https://peps.python.org/pep-0640/

Copy link
Member

@liquidcronos liquidcronos left a comment

Choose a reason for hiding this comment

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

Hey @philipp1604 , thank you for your contribution.
Definetly a promising start!
However I think there are some areas of improvement to make the main code easier to understand, extend and maintain.
For this reason I have so far only checked the class function itself.
Once these problems are resolved i will review the code again.
Feel free to message me @philipp1604 if you have any questions regarding my comment by simply replying to the comments.

import numpy as np


class Gcode_class():
Copy link
Member

Choose a reason for hiding this comment

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

This name does not specify what the class acutally models or does.
Try to be more expressive. Additionally class names should follow CamelCase naming conventions

Copy link
Member

Choose a reason for hiding this comment

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

Also dont forget to rename the python file once the class is renamed

@@ -0,0 +1,455 @@
import time
import pybullet as p
import pybullet_industrial as pi
Copy link
Member

Choose a reason for hiding this comment

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

Dont import the whole library as this can lead to cyclical imports if the library library loads the gcode class.
Instead import only what you need. Compare with the other classes for reference

"""Initialize a PathMover object with the provided parameters.

Args:
robot (pi.RobotBase): The robot to be moved.
Copy link
Member

Choose a reason for hiding this comment

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

It is "controlled" rather then "moved".
The later is ambigous since the base could also be moved and also does not include Endeffector control commands,

self.last_point = []
self.last_or = []

if m_commands is not None:
Copy link
Member

Choose a reason for hiding this comment

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

class variables should always be initialized to some value. Otherwise there might be some accessability bugs.

If no m_commands is provided simply set it to the default None value

if m_commands is not None:
self.m_commands = m_commands

if t_commands is not None:
Copy link
Member

Choose a reason for hiding this comment

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

class variables should always be initialized to some value. Otherwise there might be some accessability bugs.

If no t_commands is provided simply set it to the default None value

if position_error < 0.02 and orientation_error < 0.004:
break

def move_robot(self, path: pi.ToolPath):
Copy link
Member

Choose a reason for hiding this comment

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

almost a duplicate of the function above. Should be shortened to only include what is different to move_along_path

* len(path.orientations[0]))

# Moving endeffector or the robot
if not self.active_endeffector == -1:
Copy link
Member

Choose a reason for hiding this comment

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

both of these functions are almost identical. this is dangerous as bugs in both could only be fixed in one. Avoid the duplicates compare with the g0 function which has the same problem.

Better yet fold them into one such as in g0
Also the naming is very inconsistent it is not clear that move_along_path does the same as move_robot just with the endeffector!

for i in self.endeffector_list:

if i.is_coupled():
active_endeffector = n
Copy link
Member

Choose a reason for hiding this comment

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

why do you need n? why not set it to i?

None
"""
self.active_endeffector = self.get_active_endeffector()
e = self.active_endeffector
Copy link
Member

Choose a reason for hiding this comment

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

again choose a more expressive name

self.active_endeffector = self.get_active_endeffector()
e = self.active_endeffector

if not self.active_endeffector == -1:
Copy link
Member

Choose a reason for hiding this comment

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

again try to avoid the not by switching the if and else cases

Changes:

- Renamed Gcode_class to GCodeProcessor.
- The class has been updated based on the feedback from @liquidcronos, except for the Euler conversion and the methods for moving the end effector and robot.
- It would be beneficial to have a meeting to discuss potential solutions for running those commands outside of the GCodeProcessor
- g_code_processor class was duplicated in examples
- test_g_code_processor was duplicated in examples
- I got confused when renaming the files
- this is the correct version now

Changes:

Renamed Gcode_class to GCodeProcessor.
The class has been updated based on the feedback from @liquidcronos, except for the Euler conversion and the methods for moving the end effector and robot.
It would be beneficial to have a meeting to discuss potential solutions for running those commands outside of the GCodeProcessor.
- The class variable self.plane was renamed to self.axis
- for-loop does not need the break command
- else conditions was doubbled with the constructur of the method
- Default values and None values updated
- test class updated according to changes
Returns:
None
"""
orientation = p.getQuaternionFromEuler(self.new_or)
Copy link
Collaborator Author

@philipp1604 philipp1604 Apr 20, 2023

Choose a reason for hiding this comment

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

Comment on old gcode_class: "Make sure you check that the abc euler conversion of G-code corresponds to the Eular angle definition of pybullet. Note that there are several different euler angle defitions.
This probably warants a test case"

@liquidcronos Could you help me with this? Shouldn't the euler conversion of the pybullet always follow the default value?

Copy link
Member

Choose a reason for hiding this comment

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

There is not really a default euler conversion. Different Fields define different euler angles around different axis.
Check the wikipedia article for reference.

I believe that pybullet uses the RPY (Roll Pitch Yaw) formulation. This means that the first vector describes a rotation around the x axis, the second around the y axis and the third around the z axis. We need to make sure that the deafult g code formulation of a, b, c corresponds to the same euler angles and not a different convention.

Comment on lines 214 to 232
if self.active_endeffector == -1:
for _ in range(20):
self.robot.set_endeffector_pose(self.new_point, orientation)
for _ in range(10):
p.stepSimulation()
time.sleep(self.sleep)

current_position = self.robot.get_endeffector_pose()[0]
or_euler = p.getEulerFromQuaternion(
self.robot.get_endeffector_pose()[1])
current_orientation = np.array(or_euler)

position_error = np.linalg.norm(current_position -
self.new_point)
orientation_error = np.linalg.norm(current_orientation -
self.new_or)

if position_error < 0.02 and orientation_error < 0.004:
break
Copy link
Collaborator Author

@philipp1604 philipp1604 Apr 20, 2023

Choose a reason for hiding this comment

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

[Comment 1] old gcode_class: "Consider moving the step simulation function directly in the run_gcode function. you currently have declared it in a number of places making it hard to track.
Ideally we would even want it outside of the run_gcode function as this current implementation prevents two robots from moving simulateniously using g code (as each calls its own step simulation)
@MaHajo we should proably talk about this"

[Comment 2] It would probably be best if the run_gcode function returns a iterator that performs the loop. This would make everything much more modular and usable

@liquidcronos @MaHajo: For now, I have created several methods inside the GCodeProcessor to ensure that the robot moves to the right positions. However, I am aware that this is not an optimal solution as similar methods are scattered throughout the codebase. I agree that it would be better to have the actual settings for running the simulation outside of the GCodeProcessor. Therefore, it would be beneficial to have a meeting to discuss this topic."

- moved the default value of the offset inside the init method
Changes:
- first change of the class to be an iterable
- all the methods contain return value
- outsourcing of the read_gcode methode

Bugs:
- G-Code can be played but needs correction to fullfill the desired function
Changes:
- Draft of a new approach to treat each elementary opereation
- If a toolpath was created the iterator runs the toolpath before moving to the next command

Notations:
- This version is not debugged
Changes:

(1)
- The toolpath of the G1 commands are inserted into the gcode
- afterwards they are called like G0 operations
- this enables the positions to be simulated after each step

(2)
- each G-Code operations returns a True or False value if a a step_Simulation is needed
This is the first adjustment of using Lambda calls for elementary operations.
In the next commits the same principle will be implemented for M-,T- and G0 function.
Changes:
- T-, M-,G0/G1/G2/G3- as elementary operations

Next Step:
- every operation elementary --> G500 etc
- better code structure
- this is a draft of the new code design
- every operation in the processor is modular

Next steps:
- returning G-code line
Changes:
- Improving structure
- New G-Code Line as Return Value
- G-Code as String value
- test class was adapted to the new GCode class
- updated version of the GCodeProcessor
- create as iterable
- the iterator return elementary operations to perform
- simulation is run outsite the class
- trying to resolve build 3.8 error
The commands were changed from lists to dictionaries.
- previous checks have failed because the test class was not updated to the new dictionary convention
- in order for the code to work m_commands and t_commands have to be added as dictionaries
- if a G1/G2/G3 interpolation is peformed the interpolations steps are calculated depedning on the precision
- first a path with 1000 interpolation_steps is build so that a global distance can be determined
- global_distance/precision return the true number of interpolation_steps
- The interpolation precision was debugged
- All the tests pass
- implementation of the correct offset transformation
- file moved into pybullet folder
- including new orientation offset
- implementation of elementary operations
- implementation of interpolation precision
- commands stored in dictionary
- transformation of offset
- operations saved in lambda calls
@philipp1604 philipp1604 requested a review from liquidcronos July 17, 2023 12:05
Copy link
Collaborator Author

@philipp1604 philipp1604 left a comment

Choose a reason for hiding this comment

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

@liquidcronos @MaHajo
This is the final version of the GCodeProcessor which needs to be reviewed.
Thank you in advance!


class GCodeProcessor:

offset_def = np.array([[0.0, 0.0, 0.0], [0.0, 0.0, 0.0]])
Copy link
Collaborator Author

Choose a reason for hiding this comment

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

inside the init

Copy link
Member

@liquidcronos liquidcronos left a comment

Choose a reason for hiding this comment

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

Great, much better than the first iteration,
only a few minor things should be tweaked before approving it for merger

pysics_client = p.connect(p.GUI, options='--background_color_red=1 ' +
'--background_color_green=1 ' +
'--background_color_blue=1')
p.setPhysicsEngineParameter(numSolverIterations=10000)
Copy link
Member

Choose a reason for hiding this comment

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

This line is called twice for some reason

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

The line was removed

examples/g_code_processor_dem.py Outdated Show resolved Hide resolved
examples/g_code_processor_dem.py Outdated Show resolved Hide resolved
examples/g_code_processor_dem.py Outdated Show resolved Hide resolved
endeffector_list,
m_commands, t_commands)

for _ in demonstration_object:
Copy link
Member

Choose a reason for hiding this comment

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

I think this line is very confusing to anyone unfamiliar with the GCodeProcessor because its not clear that the for loop creates a iterator that is exectuted at every step.

Its probably better to explicitly create it and then call it. A comment explaining what happens would also be usefull

Copy link
Collaborator Author

@philipp1604 philipp1604 Jul 19, 2023

Choose a reason for hiding this comment

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

    # Create an iterator from the demonstration object
    demonstration_iterator = iter(demonstration_object)

    # Iterate over the demonstration object
    for _ in demonstration_iterator:
        # Execute the simulation steps
        for _ in range(200):
            p.stepSimulation()

src/pybullet_industrial/g_code_processor.py Outdated Show resolved Hide resolved
src/pybullet_industrial/g_code_processor.py Outdated Show resolved Hide resolved
'B': np.nan, 'C': np.nan, 'R': np.nan}

for val in cmd:
if val[0] in variables:
Copy link
Member

Choose a reason for hiding this comment

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

and if not we might want to throw an error

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

error for unknown letter adapted

src/pybullet_industrial/g_code_processor.py Show resolved Hide resolved
tests/test_g_code_processor.py Outdated Show resolved Hide resolved
- all the correction for the review where implemented
- excpect the monastry was not adapted yet
- this will update in the next commit
- All the proposed requested have been changed
@philipp1604
Copy link
Collaborator Author

Great, much better than the first iteration, only a few minor things should be tweaked before approving it for merger

Thank you very much @liquidcronos for the thorough review. Everything was implemented in the last commit and all the comments were replied with the updated changes.

@liquidcronos liquidcronos merged commit 7eb0a87 into main Jul 19, 2023
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
enhancement New feature or request
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants