Differences

This shows you the differences between two versions of the page.

Link to this comparison view

Both sides previous revisionPrevious revision
Next revision
Previous revision
tutorials:beginner:location_designators [2016/01/25 17:55] gkazhoyatutorials:beginner:location_designators [2016/03/04 14:25] (current) – old revision restored (2016/01/26 10:38) gkazhoya
Line 30: Line 30:
 We will now have a look at how to create and resolve location designators. We will now have a look at how to create and resolve location designators.
  
-===== Creating a location designator =====+===== Location designator generators =====
  
 Let's create a new file called ''location-designators.lisp'' in our tutorial's ''src'' directory and add it to the ''*.asd'' file with ''process-modules'' depending on it. The resulting ''cram-beginner-tutorial.asd'' should now look like this: Let's create a new file called ''location-designators.lisp'' in our tutorial's ''src'' directory and add it to the ''*.asd'' file with ''process-modules'' depending on it. The resulting ''cram-beginner-tutorial.asd'' should now look like this:
Line 56: Line 56:
 </code> </code>
  
-Now we'll want some code to generate a location based on a symbolic description found in a designator.+Now we'll want some code to generate a location based on a symbolic description found in a designator. There are two interfaces for resolving location designators: one analogous to action designators' ''(action-desig ?desig ?solution)'' Prolog predicate, for locations it's ''(desig-solution ?desig ?solution)'' (predicate names could've been more similar, but, oh well), the mechanism is exactly the same as for action designators. However, with Prolog rules all solutions have more or less the same priority, and if one constraint can be resolved to multiple solutions there is no way to prioritize one over the other. One use case of priorities is to always just in case check robot's current position when a pose for the robot base is being resolved: if robot's current pose is already sufficient to execute some task (location validator says '':accept'') this mechanism can save some time on re-positioning. In this case robot's current pose will always have higher priority over the rest of location generators. In this tutorial we will implement a custom generator function that can be prioritized. In fact, the solutions coming from Prolog predicate ''(desig-solution ?location-desig ?solution)'' are also implemented as a custom generator with priority 10. We will discuss priorities in more detail below.
  
 +We would like to specify locations for the turtle to go using spatial relations, e.g.:
 +<code lisp>
 +TUT> (defparameter goal-desig
 +       (make-designator :location '((:vertical-position :bottom) (:horizontal-position :left))))
 +TUT> goal-desig
 +#<LOCATION-DESIGNATOR ((:VERTICAL-POSITION :BOTTOM)
 +                       (:HORIZONTAL-POSITION :LEFT)) {1008548CD3}>
 +</code>
  
- +This way TurtleSim field will be divided into 9 areasas shown below:
-Here is an example of such a functionwhich you can append to your location-designators.lisp file:+
  
 {{ :tutorials:beginner:turtle-locations.png?direct&500 |}} {{ :tutorials:beginner:turtle-locations.png?direct&500 |}}
 +
 +Here is an example of a designator resolving function which you can append to your ''location-designators.lisp'' file:
  
 <code lisp> <code lisp>
 (in-package :tut) (in-package :tut)
  
-(defun navigation-goal-generator (location-designator) +(defun navigation-goal-generator (designator) 
-  (let ((retq ())) +  (declare (type location-designator designator)) 
-      (dotimes (k 10+  (with-desig-props (vertical-position horizontal-positiondesignator 
-          (let ((x (1)) (y (- 1))) +    (let ((x-offset (ecase horizontal-position 
-              (dolist (elem (description location-designator)+                      (:left 0
-                  (case +                      (:center (/ 11.0 3.0)) 
-                      (car elem) +                      (:right ((11.0 3.0) 2)))) 
-                          (vpos +          (y-offset (ecase vertical-position 
-                              (case (cadr elem) +                      (:bottom 0
-                                  (center (setq y (+ 6 (random 4.0) -2)) ) +                      (:center (/ 11.0 3.0)) 
-                                  (top (setq y (11 (random 4.0) -2)) ) +                      (:top ((11.0 3.0) 2))))) 
-                                  (bottom (setq y (+ 1 (random 4.0) -2))))) +      (loop repeat 5 
-                          (hpos +            collect (cl-transforms:make-3d-vector 
-                              (case (cadr elem+                     (+ x-offset (random (/ 11.3.0))
-                                  (center (setq x (+ 6 (random 4.0) -2))) +                     (+ y-offset (random (/ 11.3.0))) 
-                                  (right (setq x (11 (random 4.0) -2))) +                     0)))))
-                                  (left (setq x (+ 1 (random 4.0) -2))))))) +
-    (setq retq (append retq +
-         (list (cl-tf:make-pose-stamped +
-              "turtlesim" +
-              (roslisp:ros-time) +
-              (cl-transforms:make-3d-vector x y 0) +
-              (cl-transforms:make-quaternion 0 0 0 1))))))) +
-    (return-from navigation-goal-generator retq)))+
 </code> </code>
  
-What this function does is convert a description like, for example, ''( (vpos center) (hpos center) )'', into a pose for the turtle expressed as numeric coordinates. Note that the function expects a location designator as a parameter and returns a list of candidate positions. This is not accidental; if we want to register this function as a location-generator (which we will do, shortly), then we need to obey this interface. Even if we had wanted to return a single candidate, it should have been returned as a list, containing only one candidate. Also, and this is **very important**, elements of the result list must be stamped poses made by the cl-tf package. Already-existing software using location designators relies on results being stamped poses, and it's a good idea to use them yourself. +Let's compile the new function and test it in the REPL on the example designator:
- +
-We'll also need a validation function, and here is an example of such, which you can append to your location-designators.lisp:+
  
 <code lisp> <code lisp>
-(defun turtle-pose-validator (location-designator pose+TUT> (navigation-goal-generator goal-desig
-  (declare (ignore location-designator)) +(#<3D-VECTOR (1.0404995679855347d0 0.03507864475250244d0 0.0d0)> 
-  (when (typep pose 'cl-transforms:pose+ #<3D-VECTOR (3.0929160118103027d0 0.8247395753860474d0 0.0d0)> 
-    (if + #<3D-VECTOR (3.048727035522461d0 1.0249313116073608d0 0.0d0)> 
-     (or + #<3D-VECTOR (2.1428534984588623d0 2.775157928466797d0 0.0d0)> 
-      ((cl-transforms:+ #<3D-VECTOR (3.3696107864379883d0 0.026859402656555176d0 0.0d0)>)
-          (cl-transforms:origin pose)) +
-         0) +
-      ((cl-transforms:+
-          (cl-transforms:origin pose)) +
-         0) +
-      (> (cl-transforms:+
-          (cl-transforms:origin pose)) +
-         11.8) +
-      ((cl-transforms:y +
-          (cl-transforms:origin pose)) +
-         11.8)) +
-     (return-from turtle-pose-validator :reject) +
-     (return-from turtle-pose-validator :accept))))+
 </code> </code>
  
-This validator simply checks that the required position is inside the screen of the turtlesim. Again, the interface of the function is importantWe must declare it as taking two parameters, designator and a poseeven if, as is the case herewe don't actually use one of the parameters. Also, the return value must be one of the values listed above (:accept :reject :unknown :maybe-reject).+The function expects a location designator as a parameter and returns a list of solutions (in this case points in the bottom left corner of the TurtleSim field: points between ''0'' and ''3.667'' in ''x'' and ''y''). This is not accidental; if we want to register this function as a location generator (which we will do next)then we need to obey this interface. Even if we had wanted to return a single candidateit should have been returned as a listcontaining only one candidate.
  
-We also need to register these two functions, so append the following to location-designators.lisp:+To register the function as a location generator we simply append the following to our ''location-designators.lisp'':
  
 <code lisp> <code lisp>
 (register-location-generator (register-location-generator
- 15 navigation-goal-generator+ navigation-goal-generator)
- +
-(register-location-validation-function +
- 15 turtle-pose-validator)+
 </code> </code>
  
-The register-* functions have self explanatory names, and one of the parameters is a function name that we want to register. The number parameter is a 'priority', and it will order the calls to generators and validators. Lower numbers mean called earlier.+One of the parameters of ''cram-designators:register-location-generator'' is a function name that we want to register. The number parameter is the priority, and it will order the calls to the generators. Lower numbers mean called earlier.
  
-===== Resolving a location designator =====+Let's see if it works, don't forget to recompile the file / reload the system: 
 +<code lisp> 
 +TUT> (reference goal-desig) 
 +#<3D-VECTOR (1.142098307609558d0 2.184809684753418d0 0.0d0)> 
 +TUT> (reference goal-desig) 
 +#<3D-VECTOR (1.142098307609558d0 2.184809684753418d0 0.0d0)> 
 +</code>
  
-Let's reload the tutorial system in roslisp_repl and play with the new functions a bitLet's try to create a location designator via this call in the REPL command line:+So far so good, we get a pose, and it is in fact in the bottom left corner. However, both calls to ''reference'returned the same solution. Surely the random number generator in navigation-goal-generator didn't create the exact same numbers twiceIndeed, it didn't, but to get other candidates that survived validation we will need another function, ''next-solution'':
  
 <code lisp> <code lisp>
-TUT> (defparameter turtle-target (make-designator 'location `((vpos center) (hpos center)))) +TUT> (next-solution goal-desig) 
-TURTLE-TARGET+#<LOCATION-DESIGNATOR ((:VERTICAL-POSITION :BOTTOM) 
 +                       (:HORIZONTAL-POSITION :LEFT)) {10086B5A23}>
 </code> </code>
  
-So far so goodlet's reference it by calling in REPL's command line:+Perhaps a little confusingly, ''next-solution'' doesn't actually return the next solution, but rather a new designator, with identical properties to the first, that is associated to the next solution. If no other solution exists, then ''next-solution'' returns nil. If we actually want to see this solution, assuming it exists, we need to call:
  
 <code lisp> <code lisp>
-TUT> (reference turtle-target) +TUT> (reference (next-solution goal-desig)) 
-#<CL-TF:POSE-STAMPED  +#<3D-VECTOR (0.261885404586792d0 2.649489164352417d0 0.0d0)>
-   FRAME-ID: "turtlesim", STAMP: 1.414076190451d9 +
-   #<3D-VECTOR (5.194351673126221d0 6.093849182128906d0 0.0d0)+
-   #<QUATERNION (0.0d0 0.0d0 0.0d0 1.0d0)>> +
-TUT> (reference turtle-target+
-#<CL-TF:POSE-STAMPED  +
-   FRAME-ID: "turtlesim", STAMP: 1.414076190451d9 +
-   #<3D-VECTOR (5.194351673126221d0 6.093849182128906d0 0.0d0)> +
-   #<QUATERNION (0.0d0 0.0d0 0.0d0 1.0d0)>>+
 </code> </code>
  
-This also looks ok, we get a pose, and it's plausibly near the center. However, both calls to reference returned the same solution. Surely the random number generator in navigation-goal-generator didn't create the exact same numbers twice. Indeed, it didn't, but to get other candidates that survived validation we will need another function, next-solution:+If we called ''(reference (next-solution goal-desig))'' again, we would get this same solution againIf ''goal-desig'stayed the same, then the next solution designator also stayed the same, and so did the solution associated with it. One way to iterate over the solutions would be:
  
 <code lisp> <code lisp>
-TUT> (next-solution turtle-target+TUT> (loop for desig = goal-desig then (next-solution desig) 
-#<LOCATION-DESIGNATOR ((VPOS CENTER) (HPOS CENTER)) {100A1F3393}>+           while desig 
 +           do (print (reference desig))) 
 +#<3D-VECTOR (1.142098307609558d0 2.184809684753418d0 0.0d0) 
 +#<3D-VECTOR (0.261885404586792d0 2.649489164352417d0 0.0d0)>  
 +#<3D-VECTOR (2.560281276702881d0 1.5541117191314697d0 0.0d0)>  
 +#<3D-VECTOR (3.182616949081421d0 1.329969882965088d0 0.0d0)>  
 +#<3D-VECTOR (1.3107243776321411d0 2.9240825176239014d0 0.0d0)>  
 +NIL
 </code> </code>
  
-Perhaps little confusingly, next-solution doesn't actually return the next solution, but rather new designator, with identical properties to the first, that is associated to the next solutionIf no other solution existsthen next-solution returns nilIf we actually want to see this solution, assuming it exists, we need to call:+ 
 +===== Location designator validation ===== 
 + 
 +Now let's add validation function. The points we get from ''navigation-goal-generator'' range from ''0'' to ''11'' but whenever the turtle has coordinate above ''10.5'' part of it disappears from the screen. Let's improve our location designator resolution by rejecting the points that lie outside of the ''[0.510.5]'' range. For that append the following to your ''location-designators.lisp'' file:
  
 <code lisp> <code lisp>
-TUT> (reference (next-solution turtle-target)) +(defun navigation-goal-validator (designator solution
-#<CL-TF:POSE-STAMPED  +  (declare (type location-designator designator)) 
-   FRAME-ID"turtlesim", STAMP: 1.414076190451d9 +  (when (and (desig-prop-value designator :vertical-position) 
-   #<3D-VECTOR (6.060066223144531d0 5.841248512268066d0 0.0d0)> +             (desig-prop-value designator :horizontal-position)) 
-   #<QUATERNION (0.0d0 0.0d0 0.0d0 1.0d0)>>+    (when (typep solution 'cl-transforms:3d-vector) 
 +      (when 
 +          (and 
 +           (>= (cl-transforms:x solution) 0.5
 +           (>= (cl-transforms:y solution) 0.5
 +           (<(cl-transforms:x solution) 10.5) 
 +           (<= (cl-transforms:y solution) 10.5)) 
 +        :accept)))) 
 + 
 +(register-location-validation-function 
 + 5 navigation-goal-validator)
 </code> </code>
  
-If we called (reference (next-solution turtle-target)) againwe will get this same solution again. If turtle-target stayed the same, then the next-solution designator also stayed the same, and so did the solution associated with it. One way to iterate over the solutions would be:+If ''designator'' contains the properties for which we are checking the generated solution and if ''solution'' is of type ''3d-vector''the function will accept all the solutions that lie in the above-mentioned limits and reject everything else (''NIL'' is equivalent to '':reject'' for location validators).
  
-<code lisp> +The last function call registers our validator, validators are prioritized just as the generators.
-TUT> (setq turtle-target-copy (copy-designator turtle-target)) +
-#<LOCATION-DESIGNATOR ((HPOS CENTER) (VPOS CENTER)) {100A079C03}> +
-TUT> (loop do (setq sol (reference turtle-target-copy)) (print sol) (setq turtle-target-copy (next-solution turtle-target-copy)) while (not (equal turtle-target-copy nil))) +
-;  +
-; caught WARNING: +
-;   undefined variable: SOL +
-;  +
-; compilation unit finished +
-;   Undefined variable: +
-;     SOL +
-;   caught 1 WARNING condition+
  
-#<CL-TF:POSE-STAMPED  +Let's test if this workeddon't forget to recompile the file / reload the system
-   FRAME-ID: "turtlesim"STAMP1.414076190451d9 + 
-   #<3D-VECTOR (5.194351673126221d0 6.093849182128906d0 0.0d0)> +<code lisp
-   #<QUATERNION (0.0d0 0.0d0 0.0d0 1.0d0)>+TUT> (defparameter another-goal 
-#<CL-TF:POSE-STAMPED  +       (make-designator :location '((:vertical-position :bottom) (:horizontal-position :left)))) 
-   FRAME-ID: "turtlesim", STAMP: 1.414076190451d9 +ANOTHER-GOAL 
-   #<3D-VECTOR (6.060066223144531d0 5.841248512268066d0 0.0d0)> +TUT> (loop for desig = another-goal then (next-solution desig) 
-   #<QUATERNION (0.0d0 0.0d0 0.0d0 1.0d0)>> +           while desig 
-#<CL-TF:POSE-STAMPED  +           do (print (reference desig))) 
-   FRAME-ID"turtlesim", STAMP: 1.4140771269d9 +#<3D-VECTOR (1.5110043287277222d0 2.1800525188446045d0 0.0d0)>  
-   #<3D-VECTOR (7.604331970214844d0 7.907034873962402d0 0.0d0)> +#<3D-VECTOR (2.030768394470215d0 2.731144428253174d0 0.0d0)>  
-   #<QUATERNION (0.0d0 0.0d0 0.0d0 1.0d0)>>  +#<3D-VECTOR (0.7122993469238281d0 3.623168706893921d0 0.0d0)> 
-#<CL-TF:POSE-STAMPED  +
-   FRAME-ID"turtlesim", STAMP: 1.4140771269d9 +
-   #<3D-VECTOR (4.6705708503723145d0 5.763947486877441d0 0.0d0)+
-   #<QUATERNION (0.0d0 0.0d0 0.0d0 1.0d0)>>  +
-#<CL-TF:POSE-STAMPED  +
-   FRAME-ID"turtlesim", STAMP: 1.4140771269d9 +
-   #<3D-VECTOR (5.831815719604492d0 7.300619125366211d0 0.0d0)+
-   #<QUATERNION (0.0d0 0.0d0 0.0d0 1.0d0)>>  +
-#<CL-TF:POSE-STAMPED  +
-   FRAME-ID: "turtlesim", STAMP: 1.4140771269d9 +
-   #<3D-VECTOR (7.306698799133301d0 4.04398775100708d0 0.0d0)> +
-   #<QUATERNION (0.0d0 0.0d0 0.0d0 1.0d0)>>  +
-#<CL-TF:POSE-STAMPED  +
-   FRAME-ID: "turtlesim", STAMP: 1.4140771269d9 +
-   #<3D-VECTOR (5.219023704528809d0 4.466149806976318d0 0.0d0)+
-   #<QUATERNION (0.0d0 0.0d0 0.0d0 1.0d0)>>  +
-#<CL-TF:POSE-STAMPED  +
-   FRAME-ID: "turtlesim", STAMP: 1.4140771269d9 +
-   #<3D-VECTOR (6.606534957885742d0 4.025519847869873d0 0.0d0)> +
-   #<QUATERNION (0.0d0 0.0d0 0.0d0 1.0d0)>>  +
-#<CL-TF:POSE-STAMPED  +
-   FRAME-ID: "turtlesim", STAMP: 1.4140771269d9 +
-   #<3D-VECTOR (4.306739330291748d0 7.699792861938477d0 0.0d0)> +
-   #<QUATERNION (0.0d0 0.0d0 0.0d0 1.0d0)>>  +
-#<CL-TF:POSE-STAMPED  +
-   FRAME-ID: "turtlesim", STAMP: 1.4140771269d9 +
-   #<3D-VECTOR (7.969078063964844d0 4.372735500335693d0 0.0d0)> +
-   #<QUATERNION (0.0d0 0.0d0 0.0d0 1.0d0)>+
 NIL NIL
 </code> </code>
  
-(Note that at the end of the iterationturtle-target-copy becomes nil.)+Depending on the random number generator we will get some or none of the solutions rejected andtherefore, ''<='' number of valid solutions for our designator ''another-goal''. 
  
 ===== Using a location designator ===== ===== Using a location designator =====
  
-Let's try to create a process module to make use of a location designator as well. Append the following to process-modules.lisp:+Let's try to create a process module to make use of a location designator as well. Append the following to ''action-designators.lisp'':
  
 <code lisp> <code lisp>
-(cram-process-modules:def-process-module turtle-navigation (location-designator)+(def-fact-group goal-actions (action-desig) 
 +  (<- (action-desig ?desig (go-to ?point)) 
 +    (desig-prop ?desig (:type :goal)) 
 +    (desig-prop ?desig (:goal ?point)))) 
 +</code> 
 + 
 +This will resolve any action designator with properties ''( (:type :goal) (:goal some-location-designator) )'' into ''(go-to some-location-designator)'' instruction. 
 + 
 +Now for the process module, let's add a new process module called ''simple-navigation'' that accepts action designators with above-mentioned properties and a function ''goto-location'' that will invoke the new process module. Also, let's add ''simple-navigation'' to the running process modules in our ''with-turtle-process-modules'' macro. You ''process-modules.lisp'' should now look something like this: 
 + 
 +<code lisp> 
 +(in-package :tut) 
 + 
 +(def-process-module actionlib-navigation (action-designator)
   (roslisp:ros-info (turtle-process-modules)   (roslisp:ros-info (turtle-process-modules)
-                    "Turtle navigation invoked with location designator `~a'." +                    "Turtle shape navigation invoked with action designator `~a'." 
-                    location-designator) +                    action-designator) 
-  (let ((target-pose (reference location-designator))) +  (destructuring-bind (command action-goal) (reference action-designator
-       (print (cl-transforms:origin target-pose)) +    (ecase command 
-       (move-to (cl-transforms:origin target-pose))))+      (draw-shape 
 +       (call-shape-action 
 +        :edges (turtle-shape-edges action-goal) 
 +        :radius (turtle-shape-radius action-goal)))))) 
 + 
 +(def-process-module simple-navigation (action-designator) 
 +  (roslisp:ros-info (turtle-process-modules) 
 +                    "Turtle simple navigation invoked with action designator `~a'." 
 +                    action-designator
 +  (destructuring-bind (command action-goal) (reference action-designator) 
 +    (ecase command 
 +      (go-to 
 +       (when (typep action-goal 'location-designator) 
 +         (let ((target-point (reference action-goal))) 
 +           (roslisp:ros-info (turtle-process-modules) 
 +                             "Going to point ~a." target-point) 
 +           (move-to target-point))))))) 
 + 
 +(defmacro with-turtle-process-modules (&body body) 
 +  `(with-process-modules-running 
 +       (actionlib-navigation 
 +        simple-navigation) 
 +     ,@body))
  
-(defun goto-location (location-desig)+(defun draw-hexagon (radius)
   (let ((turtle-name "turtle1"))   (let ((turtle-name "turtle1"))
     (start-ros-node turtle-name)     (start-ros-node turtle-name)
     (init-ros-turtle turtle-name)     (init-ros-turtle turtle-name)
     (top-level     (top-level
-      (cpm:with-process-modules-running (turtle-navigation) +      (with-turtle-process-modules 
-        (cpm:process-module-alias :navigation 'turtle-navigation) +        (process-module-alias :navigation 'actionlib-navigation) 
-            (cpm:pm-execute :navigation location-desig)))))+        (with-designators 
 +            ((trajectory :action `((:type :shape) (:shape :hexagon) (:radius ,radius)))) 
 +          (pm-execute :navigation trajectory)))))) 
 + 
 +(defun goto-location (horizontal-position vertical-position) 
 +  (let ((turtle-name "turtle1")) 
 +    (start-ros-node turtle-name) 
 +    (init-ros-turtle turtle-name) 
 +    (top-level 
 +      (with-turtle-process-modules 
 +        (process-module-alias :navigation 'simple-navigation) 
 +        (with-designators 
 +            ((area :location `((:horizontal-position ,horizontal-position) 
 +                               (:vertical-position ,vertical-position))) 
 +             (goal :action `((:type :goal) (:goal ,area)))) 
 +          (pm-execute :navigation goal))))))
 </code> </code>
  
-And let's give it a go. Reload the tutorial into roslisp_repl then in the command line of REPL:+And let's give it a go. Reload the tutorial in ''roslisp_repl'' then in the command line of REPL:
  
 <code lisp> <code lisp>
-TUT> (defparameter turtle-target (make-designator 'location `((vpos center) (hpos center)))) +TUT> (goto-location :center :center
-TURTLE-TARGET +[(ROSLISP TOP) INFO] 1453758117.881: Node name is /turtle1 
-TUT> (goto-location turtle-target) +[(ROSLISP TOP) INFO] 1453758117.881: Namespace is / 
-WARNING: +[(ROSLISP TOP) INFO] 1453758117.885: Params are NIL 
-   Before starting node, node-status equalled RUNNING instead of :shutdown.  Shutting the previous node invocation down now. +[(ROSLISP TOP) INFO] 1453758117.885: Remappings are: 
-[(ROSLISP EVENT-LOOPINFO] 1414081756.703: Terminating ROS Node event loop +[(ROSLISP TOP) INFO] 1453758117.885: master URI is 127.0.0.1:11311 
-[(ROSLISP TOP) INFO] 1414081757.022: Shutdown complete +[(ROSLISP TOP) INFO] 1453758119.036: Node startup complete 
-[(ROSLISP TOP) INFO] 1414081757.028: Node name is /turtle1 +[(TURTLE-PROCESS-MODULES) INFO] 1453758119.377: Turtle simple navigation invoked with action designator 
-[(ROSLISP TOP) INFO] 1414081757.028: Namespace is / +`#<ACTION-DESIGNATOR ((TYPE GOAL) 
-[(ROSLISP TOP) INFO] 1414081757.028: Params are NIL +                      (GOAL #<LOCATION-DESIGNATOR ((HORIZONTAL-POSITION CENTER) 
-[(ROSLISP TOP) INFO] 1414081757.028: Remappings are: +                                                   (VERTICAL-POSITION CENTER)) {10095B8283}>)) {10095B87D3}>'
-[(ROSLISP TOP) INFO] 1414081757.028: master URI is 127.0.0.1:11311 +[(TURTLE-PROCESS-MODULES) INFO] 1453758119.386: Going to point #<3D-VECTOR (6.038690567016602d0 6.027290344238281d0 0.0d0)>.
-[(ROSLISP TOP) INFO] 1414081758.033: Node startup complete +
-[(TURTLE-PROCESS-MODULES) INFO] 1414081758.183: Turtle navigation invoked with location designator `#<LOCATION-DESIGNATOR ((VPOS +
-                                                                            CENTER) +
-                                                                           (HPOS +
-                                                                            CENTER)) {10078A2C53}>'+
- +
-#<CL-TRANSFORMS:3D-VECTOR (6.383428573608398d0 5.245925426483154d0 0.0d0)> +
 T T
 </code> </code>
  
-The turtle should also have moved to somewhere in the vecinity of the center of its window.+The turtle should also have moved to somewhere in the vicinity of the center of its window.
  
 == Next == == Next ==
Line 289: Line 296:
  
 [[tutorials:beginner:assigning_actions|Automatically choosing a process module for an action]] [[tutorials:beginner:assigning_actions|Automatically choosing a process module for an action]]
-