====== Primitive Skills ======
This page will refer to example skills from [[https://git.cs.lth.se/robotlab/skill_examples/-/tree/master/|this]] repository written by Pontus Rosqvist.
When it comes to SkiROS primitive skills are skills that perform some kind of computation which cannot call other skills. A primitive skill extends [[https://github.com/RVMI/skiros2/blob/master/skiros2_common/src/skiros2_common/core/primitive.py|PrimitiveBase]] which has the following stages of execution:
^ Name ^ When it runs ^ Note ^
| onInit | Once when SkiROS starts. | Compare to _ _init_ _ in a python class. |
| onStart | Once each time the skill starts. | |
| onPreempt | When a preempt signal is sent. | A preempt signal can be sent from, for example, the SkiROS gui. |
| execute | After onStart until execute returns a terminal state. | The skill should be implemented here. |
| onEnd | Once when execute has returned a terminal state. | |
An example which explains how to make a basic primitive skill can be seen in [[https://git.cs.lth.se/robotlab/skill_examples/-/blob/master/src/skill_examples/basic_primitive_skill.py|basic_primitive]] and a minimal example of a primitive skill (which can often be used as a sanity check) can be found in [[https://git.cs.lth.se/robotlab/skill_examples/-/blob/master/src/minimal_skills/minimal_primitive.py|minimal_primitive]]. A skill can both take objects from the world model as input as well as retrieve objects from the world model directly, examples of how to do this can be found in [[https://git.cs.lth.se/robotlab/skill_examples/-/blob/master/src/skill_examples/update_world_model.py|update_world_model]] and [[https://git.cs.lth.se/robotlab/skill_examples/-/blob/master/src/skill_examples/world_model_interface.py|world_model_interface]].
===== What to Think of =====
A primitive skill should be written exactly like one would write a function while programming. It should only have one purpose, there should be good error handling and it should be well documented.
If a skill executes code which cannot be run in less than 1/25th of a second the execution should be made in a new thread instead of the main one to avoid blocking the SkiROS gui from updating. If you want to write a primtive skill which performs its computations in a separate thread you can use [[https://git.cs.lth.se/robotlab/rvmi/skiros2/-/blob/non_blocking_pontus/skiros2_common/src/skiros2_common/core/primitive_thread.py|PrimitiveThreadBase]]. An example of how a skill could be implemented which uses [[https://git.cs.lth.se/robotlab/rvmi/skiros2/-/blob/non_blocking_pontus/skiros2_common/src/skiros2_common/core/primitive_thread.py|PrimitiveThreadBase]] can be seen in [[https://git.cs.lth.se/robotlab/skill_examples/-/blob/master/src/skill_examples/non_blocking_skill.py|non_blocking]]. [[https://git.cs.lth.se/robotlab/rvmi/skiros2/-/blob/non_blocking_pontus/skiros2_common/src/skiros2_common/core/primitive_thread.py|PrimitiveThreadBase]] has the same stages of execution as [[https://github.com/RVMI/skiros2/blob/master/skiros2_common/src/skiros2_common/core/primitive.py|PrimitiveBase]] but onStart has been changed to preStart and instead of implementing the skill in execute you implement the skill in run.
===== Parameters =====
A skill can have many different input parameters. What these parameters are called and what type they are is defined in the [[documentation:skiros:skill_description|skill description]]. The parameters can be accessed through the attribute self.params which is a python dict on the following form
self.params = {'PARAM1': , 'PARAM2': , ...}
The keys are the names of the parameters in the skill description while the values are the parameters which were chosen in the SkiROS gui. Example of how to extract the parameters and utilize them can be seen in [[https://git.cs.lth.se/robotlab/skill_examples/-/blob/master/src/skill_examples/basic_primitive_skill.py|basic_primitive]] and [[https://git.cs.lth.se/robotlab/skill_examples/-/blob/master/src/skill_examples/update_world_model.py|update_world_model]].
===== Return States =====
A primitive skill needs to return a terminal state to tell SkiROS that it has concluded, while the skill is running it should return the following from execute:
return self.step('MSG')
where the argument is the string that should be shown in the SkiROS gui. As long as the skill returns self.step SkiROS will continually call execute until a terminal state is returned. A terminal state is one of the following
return self.success('MSG')
return self.fail('MSG', -1)
If a skill fails while starting one can return the following error
return self.startError('MSG', -1)
An example of a skill which utilizes all of these return statements can be found in [[https://git.cs.lth.se/robotlab/skill_examples/-/blob/master/src/skill_examples/skill_return_messages.py|return_messages]]. The error code which is sent when a skill fails (the integer after the message in fail and startError) does not need to be -1 but it needs to be a negative integer.