{"id":1054,"date":"2025-08-20T09:00:35","date_gmt":"2025-08-20T09:00:35","guid":{"rendered":"https:\/\/www.astor.com.pl\/en\/?p=1054"},"modified":"2025-09-03T06:52:07","modified_gmt":"2025-09-03T06:52:07","slug":"controlling-the-astorino-robot-on-a-sphere","status":"publish","type":"post","link":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/","title":{"rendered":"Controlling the Astorino Robot on a sphere"},"content":{"rendered":"<h4><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1084 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/39.png\" alt=\"\" width=\"731\" height=\"626\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/39.png 731w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/39-300x257.png 300w\" sizes=\"auto, (max-width: 731px) 100vw, 731px\" \/><\/h4>\n<h4><strong>In this article, you will learn:<\/strong><\/h4>\n<ul>\n<li>how to simulate the motion of the Astorino robot on the surface of a sphere using the astorinoIDE software,<\/li>\n<li>how to use the mathematical description of a sphere to generate points on its surface,<\/li>\n<li>how to create a Python program that automatically calculates the robot\u2019s position and orientation on the sphere,<\/li>\n<li>how to implement motion control of the robot on the surface of a sphere in astorinoIDE.<\/li>\n<\/ul>\n<p>Thanks to this guide, you will learn how to simulate the movement of the Astorino robot over the surface of a sphere using astorinoIDE, and then implement and test the control program in real-world conditions. We\u2019ll start with the mathematical description of the robot\u2019s motion trajectory, then create Python code that calculates the robot\u2019s position and orientation on the sphere\u2019s surface. Finally, we\u2019ll transfer the program to astorinoIDE and test it on the Astorino educational robot, verifying the correctness of the movement.<\/p>\n<h4><strong>Required Equipment and Software<\/strong><\/h4>\n<ul>\n<li>astorino robot with control software,<\/li>\n<li>astorinoIDE software,<\/li>\n<li>ASTORINO-OPT-SIMBOX (for simulation testing),<\/li>\n<li>Python development environment (with NumPy library),<\/li>\n<li>PC with Windows operating system.<\/li>\n<\/ul>\n<h4><strong>Introduction<\/strong><\/h4>\n<p>Controlling a robot in three-dimensional space is a challenge, especially when precise navigation on a spherical surface is required. Robots must handle complex trajectories that may involve motion along straight lines as well as more intricate surfaces such as a sphere.<\/p>\n<p>This article presents two methods for controlling the Astorino robot to perform motion on a spherical surface. The first method involves shifting the Tool Center Point (TCP) to the center of the sphere, while the second method uses a mathematical description of the sphere along with appropriate coordinate system transformation. The following sections of the article detail how these methods are implemented in astorinoIDE and how to generate the robot\u2019s trajectory.<\/p>\n<h4><strong>Motion Control on a Sphere Based on the TCP Point<\/strong><\/h4>\n<p>The first method of controlling motion on a sphere involves moving the TCP to the center of the sphere. To do this, the tool frame (TOOL) must be offset from the robot\u2019s end-effector (tool or flange), and then the robot must be positioned in such a way that the TCP coincides with the center of the sphere. Once this position is achieved, rotating the robot around the X and Y axes of the TOOL frame results in motion along the sphere\u2019s surface. This kind of control is relatively simple but may require precise initial configuration.<\/p>\n<p>&nbsp;<\/p>\n<h3><strong>Control Based on the Mathematical Description of a Sphere<\/strong><\/h3>\n<p><em>Parameters Used to Describe a Position on the Sphere\u2019s Surface<\/em><\/p>\n<p>An alternative approach to moving the robot on a sphere is to use its mathematical description in 3D space. This can be done by defining appropriate parameters of the sphere and computing the position and orientation of points on its surface. The following notations will be used:<\/p>\n<ul>\n<li>S(x<sub>0<\/sub>,y<sub>0<\/sub>,z<sub>0<\/sub>) &#8211; center of the sphere,<\/li>\n<li>P(x,y,z) &#8211; arbitrary point on the sphere\u2019s surface,<\/li>\n<li>R<sub>k<\/sub>&#8211; radius of the sphere,<\/li>\n<li>\u03b8 &#8211; zenith angle<\/li>\n<li>\u03a6 &#8211; azimuth<\/li>\n<\/ul>\n<p>The zenith angle is the angle between the global vertical axis (Z axis) and the vector from the center of the sphere to a point on its surface. This angle is positive when measured from the Z axis in the direction of the radius leading to a given point on the sphere.<\/p>\n<p>The azimuth is the angle between the X axis and the projection of the vector leading from the center of the sphere to a point on its surface onto the XY horizontal plane. This angle is positive when measured from the X axis toward the Y axis.<\/p>\n<p>These angle definitions are illustrated below (Figure 1).<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"aligncenter wp-image-1055 size-medium\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/sterowanie-robotem-po-kuli-300x268.jpg\" alt=\"\" width=\"300\" height=\"268\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/sterowanie-robotem-po-kuli-300x268.jpg 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/sterowanie-robotem-po-kuli-368x329.jpg 368w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/sterowanie-robotem-po-kuli.jpg 692w\" sizes=\"auto, (max-width: 300px) 100vw, 300px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 1 Illustration showing the zenith angle and azimuth angle. Source: ASTOR<\/p>\n<p>Example based on the earth as a sphere:<\/p>\n<ul>\n<li>zenith angle (\u03b8) \u2013 defines the geographic latitude<\/li>\n<li>azimuth (\u03c6) \u2013 defines the geographic longitude<\/li>\n<\/ul>\n<p><strong>Mathematical description of position and orientation on a sphere<\/strong><\/p>\n<p>Using the above angular definitions, the position on the surface of a sphere can be described by the following formulas:<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"size-full wp-image-1085 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/1-1.png\" alt=\"\" width=\"319\" height=\"156\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/1-1.png 319w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/1-1-300x147.png 300w\" sizes=\"auto, (max-width: 319px) 100vw, 319px\" \/><\/p>\n<p>The tool\u2019s orientation should be defined so that its Z-axis is perpendicular to the sphere\u2019s surface and directed toward the center of the sphere.<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"size-full wp-image-1086 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/2-1.png\" alt=\"\" width=\"207\" height=\"112\" \/><\/p>\n<p>The Z-axis vector is defined as the normalized vector pointing toward the center of the sphere.<\/p>\n<p>Next, it is necessary to determine the X-axis. It will be defined as tangent to the surface of the sphere, determined based on the derivative of the position with respect to the zenith angle. If the zenith angle is constant (resulting in a zero derivative), the X-axis will be defined as the derivative of the position with respect to the azimuth angle. The following formulas are used to calculate this orientation:<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"size-full wp-image-1087 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/3-1.png\" alt=\"\" width=\"318\" height=\"294\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/3-1.png 318w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/3-1-300x277.png 300w\" sizes=\"auto, (max-width: 318px) 100vw, 318px\" \/><span style=\"font-size: 1rem\">However, if the derivative is close to zero, we take the direction of the X axis as:<\/span><\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"size-full wp-image-1088 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/4-1.png\" alt=\"\" width=\"171\" height=\"101\" \/><\/p>\n<p>In the final step, the direction of the X-axis should be recalculated to ensure the orthonormality of the tool\u2019s coordinate system.<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1089 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/5-1.png\" alt=\"\" width=\"261\" height=\"81\" \/><\/p>\n<p>Given the vectors:<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1090 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/6-1.png\" alt=\"\" width=\"225\" height=\"66\" \/><\/p>\n<p>we can construct the rotation matrix:<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1091 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/7-1.png\" alt=\"\" width=\"334\" height=\"75\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/7-1.png 334w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/7-1-300x67.png 300w\" sizes=\"auto, (max-width: 334px) 100vw, 334px\" \/><\/p>\n<p>Based on it, we can determine the Euler angles (in the ZYZ convention), which uniquely describe the orientation of the tool in 3D space.<\/p>\n<p><strong>Implementation of control in the astorinoIDE program<\/strong><\/p>\n<p>First, launch the astorinoIDE program. Select the type of connection from the dropdown list (in this example, USB connection was chosen) and click the Connect\/Disconnect button (Fig. 2).<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1092 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/8-1.png\" alt=\"\" width=\"762\" height=\"107\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/8-1.png 762w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/8-1-300x42.png 300w\" sizes=\"auto, (max-width: 762px) 100vw, 762px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 2. View of the top toolbar in astorinoIDE. Source: ASTOR<\/p>\n<p>Select the direction of data transfer from the computer to the robot and click SYNC (Fig. 3).<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1093 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/9-1.png\" alt=\"\" width=\"464\" height=\"240\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/9-1.png 464w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/9-1-300x155.png 300w\" sizes=\"auto, (max-width: 464px) 100vw, 464px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 3. View of the synchronization window for the connection between the computer and the robot. Source: ASTOR<\/p>\n<p>Next, open or create a new project from the top toolbar. To do this, click Project and choose the appropriate option from the dropdown list (Fig. 4).<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1094 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/10-1.png\" alt=\"\" width=\"793\" height=\"242\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/10-1.png 793w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/10-1-300x92.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/10-1-768x234.png 768w\" sizes=\"auto, (max-width: 793px) 100vw, 793px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 4. View of the menu for creating or opening projects. Source: ASTOR<\/p>\n<p>Then, open or create a new program. From the left folder tree, you can select an existing file from the Program Files tab or create a new program using the options in the top bar under the File tab. After choosing to create a new program (Fig. 5), a window will appear where you enter the file name and confirm with the OK button (Fig. 6).<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1056 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/11-1.png\" alt=\"\" width=\"796\" height=\"241\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/11-1.png 796w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/11-1-300x91.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/11-1-768x233.png 768w\" sizes=\"auto, (max-width: 796px) 100vw, 796px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 5. View of the program editing menu. Source: ASTOR<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1057 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/12-1.png\" alt=\"\" width=\"291\" height=\"249\" \/><\/p>\n<p style=\"text-align: center\">Fig. 6. View of the new program creation window. Source: ASTOR<\/p>\n<p>After connecting to the robot and creating your own program, you can start building the scene (the robot setup with the sphere in space). To open the simulation, click the Visualization button (Fig. 7), marked on the main program toolbar with a cube symbol.<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1095 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/13.1.png\" alt=\"\" width=\"840\" height=\"98\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/13.1.png 840w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/13.1-300x35.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/13.1-768x90.png 768w\" sizes=\"auto, (max-width: 840px) 100vw, 840px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 7 View of the astorinoIDE top toolbar. Source: ASTOR<\/p>\n<p>After clicking, a window with the robot should appear (Fig. 8).<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-large wp-image-1058 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/13-1-1024x662.png\" alt=\"\" width=\"1024\" height=\"662\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/13-1-1024x662.png 1024w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/13-1-300x194.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/13-1-768x496.png 768w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/13-1-216x140.png 216w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/13-1.png 1131w\" sizes=\"auto, (max-width: 1024px) 100vw, 1024px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 8. View of the robot simulation window. Source: ASTOR<\/p>\n<p>To facilitate robot control, we can bring it to the home position. This procedure allows for quickly returning the robot to its starting position, which simplifies further programming and command execution. To do this, in the terminal at the bottom of the astorinoIDE program (Fig. 9), type the command home and confirm by pressing Enter on the keyboard.<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-large wp-image-1059 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/14-1-1024x104.png\" alt=\"\" width=\"1024\" height=\"104\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/14-1-1024x104.png 1024w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/14-1-300x31.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/14-1-768x78.png 768w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/14-1.png 1266w\" sizes=\"auto, (max-width: 1024px) 100vw, 1024px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 9. View of the terminal window with the home command entered (click to enlarge). Source: ASTOR<\/p>\n<p>After issuing this command, the terminal should respond with the message \u201cDO motion Completed\u201d (Fig. 10), and the robot should move to the home position (Fig. 11).<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-large wp-image-1060 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/15-1-1024x92.png\" alt=\"\" width=\"1024\" height=\"92\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/15-1-1024x92.png 1024w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/15-1-300x27.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/15-1-768x69.png 768w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/15-1-1536x137.png 1536w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/15-1.png 1757w\" sizes=\"auto, (max-width: 1024px) 100vw, 1024px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 10. View of the terminal window after executing the move to home position (click to enlarge). Source: ASTOR<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-large wp-image-1061 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/16-1-1024x662.png\" alt=\"\" width=\"1024\" height=\"662\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/16-1-1024x662.png 1024w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/16-1-300x194.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/16-1-768x497.png 768w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/16-1-216x140.png 216w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/16-1.png 1133w\" sizes=\"auto, (max-width: 1024px) 100vw, 1024px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 11. View of the robot simulation window after moving to the home position. Source: ASTOR<\/p>\n<p>NOTE! Remember that for the movement to be executed, the robot must be in Repeat Mode. You can change this in the top toolbar under: Mode -&gt; Switch to Repeat (robot icon) (Fig. 12).<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1062 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/17-1.png\" alt=\"\" width=\"796\" height=\"146\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/17-1.png 796w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/17-1-300x55.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/17-1-768x141.png 768w\" sizes=\"auto, (max-width: 796px) 100vw, 796px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 12. View of the top toolbar in astorinoIDE when changing the movement mode. Source: ASTOR<\/p>\n<p>Once the project with your program and the simulation window are open, you can add a sample sphere that the robot will later move around. To do this, in the visualization window select the option Open Shape Generator (Fig. 13).<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-large wp-image-1063 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/18-1-1024x78.png\" alt=\"\" width=\"1024\" height=\"78\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/18-1-1024x78.png 1024w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/18-1-300x23.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/18-1-768x58.png 768w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/18-1.png 1116w\" sizes=\"auto, (max-width: 1024px) 100vw, 1024px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 13. View of the top bar of the robot simulation window. Source: ASTOR<\/p>\n<p>&nbsp;<\/p>\n<p>A shape creation window will open on the right side of the simulation. To add a sphere, select the Sphere tab (Fig. 14). Then you can enter its parameters: name, radius, position in the three global coordinate axes, color, and object type:<\/p>\n<ul>\n<li>Obstacle &#8211; these are static objects on the scene,<\/li>\n<li>Work &#8211; these objects can be moved by the robot,<\/li>\n<li>Tool &#8211; these objects always move along with the robot\u2019s end effector.<\/li>\n<\/ul>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1064 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/19-1.png\" alt=\"\" width=\"281\" height=\"331\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/19-1.png 281w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/19-1-255x300.png 255w\" sizes=\"auto, (max-width: 281px) 100vw, 281px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 14. View of the shape generator window in astorinoIDE. Source: ASTOR<\/p>\n<p>After setting all parameters, click the<strong> Add <\/strong>button.<\/p>\n<p><strong>Moving on the Sphere by Rotating Around a Distant TCP Point<\/strong><\/p>\n<p>The first method of moving on the sphere is to move the TCP point away by a distance equal to the sphere\u2019s radius. To do this, open the Robot Manager window (Fig. 15).<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1065 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/20-1.png\" alt=\"\" width=\"795\" height=\"102\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/20-1.png 795w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/20-1-300x38.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/20-1-768x99.png 768w\" sizes=\"auto, (max-width: 795px) 100vw, 795px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 15. View of the top toolbar in astorinoIDE. Source: ASTOR<\/p>\n<p>Once the window appears, go to the TOOL tab on the right side (Fig. 16) and enter the previously set sphere radius value for the TOOL Z parameter.<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1066 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/21-1.png\" alt=\"\" width=\"619\" height=\"516\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/21-1.png 619w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/21-1-300x250.png 300w\" sizes=\"auto, (max-width: 619px) 100vw, 619px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 16. View of the TOOL tab in the Robot Manager window. Source: ASTOR<\/p>\n<p>Click <strong>Upload Tool <\/strong>and confirm the tool change after the warning appears.<\/p>\n<p>Next, move the robot so that the TCP point coincides with the center of the sphere and the tool orientation is perpendicular to the sphere\u2019s surface. You can use the JOG tab in the Robot Manager window to do this (Fig. 17). Choose the coordinate system you want to use to move the robot from the dropdown list (Jogging -&gt; Mode), and use the buttons to move it to the position mentioned earlier (Fig. 18). This is possible only after switching the mode to Teach Mode.<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1067 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/22.png\" alt=\"\" width=\"621\" height=\"515\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/22.png 621w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/22-300x249.png 300w\" sizes=\"auto, (max-width: 621px) 100vw, 621px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 17. View of the JOG tab in the Robot Manager window. Source: ASTOR<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1068 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/23.png\" alt=\"\" width=\"770\" height=\"632\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/23.png 770w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/23-300x246.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/23-768x630.png 768w\" sizes=\"auto, (max-width: 770px) 100vw, 770px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 18. View of the robot simulation after moving to the sphere\u2019s surface. Source: ASTOR<\/p>\n<p>Then you can move the robot along the sphere. To do this, in the JOG tab, select movement in the TOOL coordinate system and perform rotations around the X and Y axes (rotation around the Z axis is not meaningful here, since it was previously aligned perpendicular to the sphere\u2019s surface). Below are some example robot positions.<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1069 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/24.png\" alt=\"\" width=\"806\" height=\"637\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/24.png 806w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/24-300x237.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/24-768x607.png 768w\" sizes=\"auto, (max-width: 806px) 100vw, 806px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 19. Example robot position no. 1. Source: ASTOR<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1070 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/25.png\" alt=\"\" width=\"840\" height=\"610\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/25.png 840w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/25-300x218.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/25-768x558.png 768w\" sizes=\"auto, (max-width: 840px) 100vw, 840px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 20. Example robot position no. 2. Source: ASTOR<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1071 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/26.png\" alt=\"\" width=\"811\" height=\"628\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/26.png 811w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/26-300x232.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/26-768x595.png 768w\" sizes=\"auto, (max-width: 811px) 100vw, 811px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 21. Example robot position no. 3. Source: ASTOR<\/p>\n<p><strong>Movement on the sphere using Its mathematical description<\/strong><\/p>\n<p>The second method for moving the robot along the sphere is generating points (position and orientation) based on the description provided earlier in the article. A Python program was written for this purpose, which generates points on the surface of the sphere along with the orientation of the TOOL coordinate system.<\/p>\n<p>&nbsp;<\/p>\n<p><strong>Note!<\/strong> If the position or orientation of the TOOL coordinate system has been changed, as in the previous section, it should be reset to the default settings (by zeroing each position and orientation component &#8211; Fig. 22).<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1072 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/27.png\" alt=\"\" width=\"618\" height=\"511\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/27.png 618w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/27-300x248.png 300w\" sizes=\"auto, (max-width: 618px) 100vw, 618px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 22. View of the Tool tab in the Robot Manager window. Source: ASTOR<\/p>\n<p>The versatility of the developed code allows calculating the position and orientation of the tool coordinate system in spherical space, regardless of the sphere\u2019s position or radius. This enables calculating coordinates of points on the sphere\u2019s surface in various configurations.<\/p>\n<p>However, it should be noted that the program does not consider the actual robot constraints, such as its physical movement capabilities, reach, or tilts. In practice, this means the points provided by the program may not always be reachable by the robot under real conditions. The program only provides mathematical results referring to an ideal mathematical sphere model, without considering physical limitations of the robot, such as kinematics, reach, or mechanical constraints.<\/p>\n<p>Thus, there is a need for further verification of the results in the context of real robot trajectories for specific applications. This article focuses on the implementation of the motion itself, not on specific applications.<\/p>\n<p>To simplify the code and avoid overly complex names, the following notations were used:<\/p>\n<ul>\n<li>Zenith angle: \u03b8 = u<\/li>\n<li>Azimuth: \u03a6 = v<\/li>\n<\/ul>\n<p>Below is the Python code that generates a selected number of points on the surface of a sphere with any previously chosen parameters:<\/p>\n<p>import numpy as np<\/p>\n<p>from scipy.spatial.transform import Rotation as R<\/p>\n<p>&nbsp;<\/p>\n<p>#<em>Sphere parameters<\/em><\/p>\n<p>x0, y0, z0 = 0.0, 500.0, 250.0\u00a0 # center of the sphere<\/p>\n<p>R_sphere = 50.0\u00a0 # radius<\/p>\n<p>N = 20\u00a0 # number of points<\/p>\n<p>&nbsp;<\/p>\n<p>for i in range(N):<\/p>\n<p>u = i * np.pi \/ (N &#8211; 1)\u00a0 # zenith angle<\/p>\n<p>v = np.pi\u00a0 # azimuth<\/p>\n<p>&nbsp;<\/p>\n<p>#Position on the sphere surface<\/p>\n<p>x = x0 + R_sphere * np.sin(u) * np.cos(v)<\/p>\n<p>y = y0 + R_sphere * np.sin(u) * np.sin(v)<\/p>\n<p>z = z0 + R_sphere * np.cos(u)<\/p>\n<p>position = np.array([x, y, z])<\/p>\n<p>center = np.array([x0, y0, z0])<\/p>\n<p>&nbsp;<\/p>\n<p>#TOOL Z axis (towards sphere center)<\/p>\n<p>Z_tool = center &#8211; position<\/p>\n<p>Z_tool \/= np.linalg.norm(Z_tool)<\/p>\n<p>&nbsp;<\/p>\n<p>#Two tangent vectors to the surface (derivatives w.r.t u and v)<\/p>\n<p>dP_du = np.array([<\/p>\n<p>R_sphere * np.cos(u) * np.cos(v),<\/p>\n<p>R_sphere * np.cos(u) * np.sin(v),<\/p>\n<p>-R_sphere * np.sin(u)<\/p>\n<p>])<\/p>\n<p>dP_dv = np.array([<\/p>\n<p>-R_sphere * np.sin(u) * np.sin(v),<\/p>\n<p>R_sphere * np.sin(u) * np.cos(v),<\/p>\n<p>0.0<\/p>\n<p>])<\/p>\n<p>&nbsp;<\/p>\n<p>#Choose one tangent vector (e.g., dP_dv)<\/p>\n<p>tangent = dP_dv<\/p>\n<p>if np.linalg.norm(tangent) &lt; 1e-6:\u00a0 # safeguard against zero vector<\/p>\n<p>tangent = dP_du<\/p>\n<p>tangent \/= np.linalg.norm(tangent)<\/p>\n<p>&nbsp;<\/p>\n<p>#Build coordinate system<\/p>\n<p>X_tool = tangent<\/p>\n<p>Y_tool = np.cross(Z_tool, X_tool)<\/p>\n<p>Y_tool \/= np.linalg.norm(Y_tool)<\/p>\n<p>X_tool = np.cross(Y_tool, Z_tool)<\/p>\n<p>X_tool \/= np.linalg.norm(X_tool)<\/p>\n<p>&nbsp;<\/p>\n<p>#Rotation matrix and conversion to Euler angles<\/p>\n<p>R_matrix = np.column_stack((X_tool, Y_tool, Z_tool))<\/p>\n<p>rot = R.from_matrix(R_matrix)<\/p>\n<p>euler_deg = rot.as_euler(&#8216;zyz&#8217;, degrees=True)<\/p>\n<p>&nbsp;<\/p>\n<p>#Output format: x,y,z,roll,pitch,yaw<\/p>\n<p>print(f&#8221;{x:.3f},{y:.3f},{z:.3f},{euler_deg[2]:.3f},{euler_deg[1]:.3f},{euler_deg[0]:.3f}&#8221;)<\/p>\n<p>The program calculates positions and orientations of a set of points located on the sphere surface. Initially, it defines basic parameters of the sphere: its center in 3D space, radius, and the number of points to be distributed on the surface.<\/p>\n<p>Then, in a loop, it calculates the exact position of each point on the sphere, changing only the zenith angle while keeping the azimuth constant. This way, the points are distributed along one meridian. For each point on the sphere, a vector is calculated pointing from the point towards the sphere\u2019s center. This vector determines the direction the tool or the local coordinate system \u201clooks\u201d at \u2014 this is the Z axis of the local frame.<\/p>\n<p>To define full orientation in space, the X and Y axes are also needed. For this, two tangent vectors to the sphere surface are computed as derivatives of the point\u2019s position with respect to the spherical angles. One of these tangent vectors is selected as the base for the X axis; if its length is too small, the other vector is chosen. The selected vector is normalized to length 1.<\/p>\n<p>Next, an orthogonal coordinate system is constructed. The Y axis is determined as perpendicular to both the Z axis and the chosen tangent vector, and then the X axis is recalculated to ensure the three axes form a consistent right-handed coordinate system. These three vectors create a rotation matrix describing how the local coordinate system at the point is oriented relative to the global system. Finally, Euler angles are extracted from this matrix, describing the orientation as a sequence of rotations around axes. The position and these three angles are printed out, providing complete spatial information.<\/p>\n<p>To verify the correctness of the generated points, a simple program was developed in astorinoIDE that uses three of the previously calculated points on the sphere surface. The program performs the robot\u2019s movement along an arc, where the first point is the start point, the second is an auxiliary point, and the third is the endpoint. This method allows visually checking if the robot correctly follows the designated trajectory. Below is the code for the program executing this movement:<\/p>\n<p>.PROGRAM SPHERE<\/p>\n<p>HOME<\/p>\n<p>lappro P1, 100<\/p>\n<p>lmove P1<\/p>\n<p>c1move P2<\/p>\n<p>c2move P3<\/p>\n<p>ldepart 100<\/p>\n<p>.END<\/p>\n<p>To transfer the calculated points into astorinoIDE, it is enough to copy the desired points returned by the Python program\u2019s output. After generating the points, they must be manually entered into the robot environment, allowing further use in subsequent application stages. Below is an example of output after compiling the Python code (Fig. 23).<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-large wp-image-1073 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/28-1024x324.png\" alt=\"\" width=\"1024\" height=\"324\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/28-1024x324.png 1024w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/28-300x95.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/28-768x243.png 768w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/28.png 1434w\" sizes=\"auto, (max-width: 1024px) 100vw, 1024px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 23. Sample output from the Python program compilation for the example parameters (click to enlarge). Source: ASTOR<\/p>\n<p>Note the warning indicating the detection of a \u201cgimbal lock\u201d during the conversion of rotation to Euler angles in the \u2018zyz\u2019 system. This means one rotation axis coincides with another, making one angle (the third) ambiguous and therefore set to zero.<\/p>\n<p>If you want to transfer the first point to astorinoIDE, use the POINT and TRANS commands in the terminal (Fig. 24).<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-large wp-image-1074 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/29-1024x101.png\" alt=\"\" width=\"1024\" height=\"101\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/29-1024x101.png 1024w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/29-300x29.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/29-768x75.png 768w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/29-1536x151.png 1536w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/29.png 1762w\" sizes=\"auto, (max-width: 1024px) 100vw, 1024px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 24. Terminal window with instruction to create a new point (click to enlarge). Source: ASTOR<\/p>\n<p>After confirming with Enter, the point will be saved. To check if this indeed happened, go to the Points -&gt; Transformation tab. A window will display saved points (Fig. 25), where you should see your saved point as below:<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1075 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/30.png\" alt=\"\" width=\"993\" height=\"217\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/30.png 993w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/30-300x66.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/30-768x168.png 768w\" sizes=\"auto, (max-width: 993px) 100vw, 993px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 25. Cartesian points window in astorinoIDE. Source: ASTOR<\/p>\n<p>Repeat this process for the other two points. It is important that each point is declared under a different index, e.g., p2, p3, etc., to maintain consistency in the program and enable proper assignment to spatial positions of the robot.<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1076 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/31.png\" alt=\"\" width=\"997\" height=\"217\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/31.png 997w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/31-300x65.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/31-768x167.png 768w\" sizes=\"auto, (max-width: 997px) 100vw, 997px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 26. Cartesian points window in astorinoIDE. Source: ASTOR<\/p>\n<p>To test the program, start the cycle by clicking the Cycle Start button.<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1077 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/32.png\" alt=\"\" width=\"796\" height=\"110\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/32.png 796w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/32-300x41.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/32-768x106.png 768w\" sizes=\"auto, (max-width: 796px) 100vw, 796px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 27. Top toolbar view in astorinoIDE. Source: ASTOR<\/p>\n<p>If you want to run the program from the beginning or from a specific step (not the first one), press Pause then Cycle Stop. Then select the code line from the Step dropdown menu where you want to start execution. Start the movement by clicking Pause, then Cycle Start.<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1078 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/33.png\" alt=\"\" width=\"799\" height=\"140\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/33.png 799w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/33-300x53.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/33-768x135.png 768w\" sizes=\"auto, (max-width: 799px) 100vw, 799px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 28. Top toolbar view in astorinoIDE. Source: ASTOR<\/p>\n<p>The program result is shown in the figure below:<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1079 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/34.png\" alt=\"\" width=\"970\" height=\"629\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/34.png 970w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/34-300x195.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/34-768x498.png 768w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/34-216x140.png 216w\" sizes=\"auto, (max-width: 970px) 100vw, 970px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 29. Example program running a movement on the sphere with trajectory no. 1 highlighted. Source: ASTOR<\/p>\n<p>Analysis shows the azimuth value remains constant (Fig. 29), while the zenith angle changes from 0 to about 90, with the last point characterized by this angle. The movement occurs only in the XZ plane (for y = const. = y0).<\/p>\n<p>The program was also tested for other zenith and azimuth angle values. This time the following zenith \u03b8 and azimuth \u03a6 values were used:<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1080 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/35.png\" alt=\"\" width=\"212\" height=\"167\" \/><\/p>\n<p>The azimuth value changes in the loop according to the formula:<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1081 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/36.png\" alt=\"\" width=\"248\" height=\"77\" \/><\/p>\n<p>The corresponding Python code line is:<\/p>\n<p style=\"text-align: center\">v = -np.pi \/ 2 + i * (np.pi \/ 2) \/ (N &#8211; 1))<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1082 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/37.png\" alt=\"\" width=\"740\" height=\"623\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/37.png 740w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/37-300x253.png 300w\" sizes=\"auto, (max-width: 740px) 100vw, 740px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 30. Example program running movement on the sphere with trajectory no. 2 highlighted. Source: ASTOR<\/p>\n<p>In this case (Fig. 30), the zenith angle remains constant, causing movement in the XY plane (for z = const. = z0).<\/p>\n<p>Below are two other generated trajectories:<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1083 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/38.png\" alt=\"\" width=\"815\" height=\"624\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/38.png 815w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/38-300x230.png 300w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/38-768x588.png 768w\" sizes=\"auto, (max-width: 815px) 100vw, 815px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 31. Example program running movement on the sphere with trajectory no. 3 highlighted. Source: ASTOR<\/p>\n<p><img loading=\"lazy\" decoding=\"async\" class=\"alignnone size-full wp-image-1084 aligncenter\" src=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/39.png\" alt=\"\" width=\"731\" height=\"626\" srcset=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/39.png 731w, https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/39-300x257.png 300w\" sizes=\"auto, (max-width: 731px) 100vw, 731px\" \/><\/p>\n<p style=\"text-align: center\">Fig. 32. Example program running movement on the sphere with trajectory no. 4 highlighted. Source: ASTOR<\/p>\n<p>This article presented two methods for controlling the Astorino robot over a sphere\u2019s surface, each with advantages and limitations. The first method is simpler and more intuitive, based on straightforward geometric calculations. The second method, although more complex, allows for greater flexibility and precision, as it enables the generation of points and tool orientation based on the mathematical description of a sphere.<\/p>\n<p>The practical implementation of control in the astorinoIDE software allows for the simulation of the robot\u2019s movements, which is essential for testing the correctness of trajectories before they are executed in the real world. Both the control methods and the implementation in astorinoIDE provide a solid foundation for the further development of Astorino robot control technology on spherical surfaces. In the future, they can be adapted for more advanced applications that require precise motion along more complex trajectories or even within spaces of more intricate shapes.<\/p>\n","protected":false},"excerpt":{"rendered":"<p>In this article, you will learn: how to simulate the motion of the Astorino robot on the surface of a sphere using the astorinoIDE software, how to use the mathematical description of a sphere to generate points on its surface, how to create a Python program that automatically calculates the robot\u2019s position and orientation on<a href=\"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/\">Continue reading <span class=\"sr-only\">&#8220;Controlling the Astorino Robot on a sphere&#8221;<\/span><\/a><\/p>\n","protected":false},"author":32,"featured_media":1084,"comment_status":"closed","ping_status":"closed","sticky":false,"template":"","format":"standard","meta":{"_acf_changed":false,"footnotes":""},"categories":[17],"tags":[],"class_list":["post-1054","post","type-post","status-publish","format-standard","has-post-thumbnail","hentry","category-articles"],"acf":[],"yoast_head":"<!-- This site is optimized with the Yoast SEO plugin v27.3 - https:\/\/yoast.com\/product\/yoast-seo-wordpress\/ -->\r\n<title>Controlling the Astorino Robot on a sphere - ASTOR EN<\/title>\r\n<meta name=\"robots\" content=\"index, follow, max-snippet:-1, max-image-preview:large, max-video-preview:-1\" \/>\r\n<link rel=\"canonical\" href=\"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/\" \/>\r\n<meta property=\"og:locale\" content=\"en_GB\" \/>\r\n<meta property=\"og:type\" content=\"article\" \/>\r\n<meta property=\"og:title\" content=\"Controlling the Astorino Robot on a sphere - ASTOR EN\" \/>\r\n<meta property=\"og:description\" content=\"In this article, you will learn: how to simulate the motion of the Astorino robot on the surface of a sphere using the astorinoIDE software, how to use the mathematical description of a sphere to generate points on its surface, how to create a Python program that automatically calculates the robot\u2019s position and orientation onContinue reading &quot;Controlling the Astorino Robot on a sphere&quot;\" \/>\r\n<meta property=\"og:url\" content=\"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/\" \/>\r\n<meta property=\"og:site_name\" content=\"ASTOR EN\" \/>\r\n<meta property=\"article:published_time\" content=\"2025-08-20T09:00:35+00:00\" \/>\r\n<meta property=\"article:modified_time\" content=\"2025-09-03T06:52:07+00:00\" \/>\r\n<meta property=\"og:image\" content=\"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/39.png\" \/>\r\n\t<meta property=\"og:image:width\" content=\"731\" \/>\r\n\t<meta property=\"og:image:height\" content=\"626\" \/>\r\n\t<meta property=\"og:image:type\" content=\"image\/png\" \/>\r\n<meta name=\"author\" content=\"Kamila Piechocka\" \/>\r\n<meta name=\"twitter:card\" content=\"summary_large_image\" \/>\r\n<meta name=\"twitter:label1\" content=\"Written by\" \/>\n\t<meta name=\"twitter:data1\" content=\"Kamila Piechocka\" \/>\n\t<meta name=\"twitter:label2\" content=\"Estimated reading time\" \/>\n\t<meta name=\"twitter:data2\" content=\"24 minutes\" \/>\r\n<script type=\"application\/ld+json\" class=\"yoast-schema-graph\">{\"@context\":\"https:\\\/\\\/schema.org\",\"@graph\":[{\"@type\":\"Article\",\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/articles\\\/controlling-the-astorino-robot-on-a-sphere\\\/#article\",\"isPartOf\":{\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/articles\\\/controlling-the-astorino-robot-on-a-sphere\\\/\"},\"author\":{\"name\":\"Kamila Piechocka\",\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/#\\\/schema\\\/person\\\/552c107ab283dcfed3d15368f7d1167d\"},\"headline\":\"Controlling the Astorino Robot on a sphere\",\"datePublished\":\"2025-08-20T09:00:35+00:00\",\"dateModified\":\"2025-09-03T06:52:07+00:00\",\"mainEntityOfPage\":{\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/articles\\\/controlling-the-astorino-robot-on-a-sphere\\\/\"},\"wordCount\":3378,\"image\":{\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/articles\\\/controlling-the-astorino-robot-on-a-sphere\\\/#primaryimage\"},\"thumbnailUrl\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/wp-content\\\/uploads\\\/2025\\\/08\\\/39.png\",\"articleSection\":[\"Articles\"],\"inLanguage\":\"en-GB\"},{\"@type\":\"WebPage\",\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/articles\\\/controlling-the-astorino-robot-on-a-sphere\\\/\",\"url\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/articles\\\/controlling-the-astorino-robot-on-a-sphere\\\/\",\"name\":\"Controlling the Astorino Robot on a sphere - ASTOR EN\",\"isPartOf\":{\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/#website\"},\"primaryImageOfPage\":{\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/articles\\\/controlling-the-astorino-robot-on-a-sphere\\\/#primaryimage\"},\"image\":{\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/articles\\\/controlling-the-astorino-robot-on-a-sphere\\\/#primaryimage\"},\"thumbnailUrl\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/wp-content\\\/uploads\\\/2025\\\/08\\\/39.png\",\"datePublished\":\"2025-08-20T09:00:35+00:00\",\"dateModified\":\"2025-09-03T06:52:07+00:00\",\"author\":{\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/#\\\/schema\\\/person\\\/552c107ab283dcfed3d15368f7d1167d\"},\"breadcrumb\":{\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/articles\\\/controlling-the-astorino-robot-on-a-sphere\\\/#breadcrumb\"},\"inLanguage\":\"en-GB\",\"potentialAction\":[{\"@type\":\"ReadAction\",\"target\":[\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/articles\\\/controlling-the-astorino-robot-on-a-sphere\\\/\"]}]},{\"@type\":\"ImageObject\",\"inLanguage\":\"en-GB\",\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/articles\\\/controlling-the-astorino-robot-on-a-sphere\\\/#primaryimage\",\"url\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/wp-content\\\/uploads\\\/2025\\\/08\\\/39.png\",\"contentUrl\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/wp-content\\\/uploads\\\/2025\\\/08\\\/39.png\",\"width\":731,\"height\":626},{\"@type\":\"BreadcrumbList\",\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/articles\\\/controlling-the-astorino-robot-on-a-sphere\\\/#breadcrumb\",\"itemListElement\":[{\"@type\":\"ListItem\",\"position\":1,\"name\":\"Home\",\"item\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/\"},{\"@type\":\"ListItem\",\"position\":2,\"name\":\"Articles\",\"item\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/articles\\\/\"},{\"@type\":\"ListItem\",\"position\":3,\"name\":\"Controlling the Astorino Robot on a sphere\"}]},{\"@type\":\"WebSite\",\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/#website\",\"url\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/\",\"name\":\"ASTOR EN\",\"description\":\"technology meets people\",\"potentialAction\":[{\"@type\":\"SearchAction\",\"target\":{\"@type\":\"EntryPoint\",\"urlTemplate\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/?s={search_term_string}\"},\"query-input\":{\"@type\":\"PropertyValueSpecification\",\"valueRequired\":true,\"valueName\":\"search_term_string\"}}],\"inLanguage\":\"en-GB\"},{\"@type\":\"Person\",\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/#\\\/schema\\\/person\\\/552c107ab283dcfed3d15368f7d1167d\",\"name\":\"Kamila Piechocka\",\"image\":{\"@type\":\"ImageObject\",\"inLanguage\":\"en-GB\",\"@id\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/wp-content\\\/uploads\\\/2025\\\/09\\\/cropped-IMG_E3610-12-Srednie-96x96.png\",\"url\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/wp-content\\\/uploads\\\/2025\\\/09\\\/cropped-IMG_E3610-12-Srednie-96x96.png\",\"contentUrl\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/wp-content\\\/uploads\\\/2025\\\/09\\\/cropped-IMG_E3610-12-Srednie-96x96.png\",\"caption\":\"Kamila Piechocka\"},\"url\":\"https:\\\/\\\/www.astor.com.pl\\\/en\\\/author\\\/kamilapiechocka\\\/\"}]}<\/script>\r\n<!-- \/ Yoast SEO plugin. -->","yoast_head_json":{"title":"Controlling the Astorino Robot on a sphere - ASTOR EN","robots":{"index":"index","follow":"follow","max-snippet":"max-snippet:-1","max-image-preview":"max-image-preview:large","max-video-preview":"max-video-preview:-1"},"canonical":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/","og_locale":"en_GB","og_type":"article","og_title":"Controlling the Astorino Robot on a sphere - ASTOR EN","og_description":"In this article, you will learn: how to simulate the motion of the Astorino robot on the surface of a sphere using the astorinoIDE software, how to use the mathematical description of a sphere to generate points on its surface, how to create a Python program that automatically calculates the robot\u2019s position and orientation onContinue reading \"Controlling the Astorino Robot on a sphere\"","og_url":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/","og_site_name":"ASTOR EN","article_published_time":"2025-08-20T09:00:35+00:00","article_modified_time":"2025-09-03T06:52:07+00:00","og_image":[{"width":731,"height":626,"url":"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/39.png","type":"image\/png"}],"author":"Kamila Piechocka","twitter_card":"summary_large_image","twitter_misc":{"Written by":"Kamila Piechocka","Estimated reading time":"24 minutes"},"schema":{"@context":"https:\/\/schema.org","@graph":[{"@type":"Article","@id":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/#article","isPartOf":{"@id":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/"},"author":{"name":"Kamila Piechocka","@id":"https:\/\/www.astor.com.pl\/en\/#\/schema\/person\/552c107ab283dcfed3d15368f7d1167d"},"headline":"Controlling the Astorino Robot on a sphere","datePublished":"2025-08-20T09:00:35+00:00","dateModified":"2025-09-03T06:52:07+00:00","mainEntityOfPage":{"@id":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/"},"wordCount":3378,"image":{"@id":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/#primaryimage"},"thumbnailUrl":"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/39.png","articleSection":["Articles"],"inLanguage":"en-GB"},{"@type":"WebPage","@id":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/","url":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/","name":"Controlling the Astorino Robot on a sphere - ASTOR EN","isPartOf":{"@id":"https:\/\/www.astor.com.pl\/en\/#website"},"primaryImageOfPage":{"@id":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/#primaryimage"},"image":{"@id":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/#primaryimage"},"thumbnailUrl":"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/39.png","datePublished":"2025-08-20T09:00:35+00:00","dateModified":"2025-09-03T06:52:07+00:00","author":{"@id":"https:\/\/www.astor.com.pl\/en\/#\/schema\/person\/552c107ab283dcfed3d15368f7d1167d"},"breadcrumb":{"@id":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/#breadcrumb"},"inLanguage":"en-GB","potentialAction":[{"@type":"ReadAction","target":["https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/"]}]},{"@type":"ImageObject","inLanguage":"en-GB","@id":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/#primaryimage","url":"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/39.png","contentUrl":"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/08\/39.png","width":731,"height":626},{"@type":"BreadcrumbList","@id":"https:\/\/www.astor.com.pl\/en\/articles\/controlling-the-astorino-robot-on-a-sphere\/#breadcrumb","itemListElement":[{"@type":"ListItem","position":1,"name":"Home","item":"https:\/\/www.astor.com.pl\/en\/"},{"@type":"ListItem","position":2,"name":"Articles","item":"https:\/\/www.astor.com.pl\/en\/articles\/"},{"@type":"ListItem","position":3,"name":"Controlling the Astorino Robot on a sphere"}]},{"@type":"WebSite","@id":"https:\/\/www.astor.com.pl\/en\/#website","url":"https:\/\/www.astor.com.pl\/en\/","name":"ASTOR EN","description":"technology meets people","potentialAction":[{"@type":"SearchAction","target":{"@type":"EntryPoint","urlTemplate":"https:\/\/www.astor.com.pl\/en\/?s={search_term_string}"},"query-input":{"@type":"PropertyValueSpecification","valueRequired":true,"valueName":"search_term_string"}}],"inLanguage":"en-GB"},{"@type":"Person","@id":"https:\/\/www.astor.com.pl\/en\/#\/schema\/person\/552c107ab283dcfed3d15368f7d1167d","name":"Kamila Piechocka","image":{"@type":"ImageObject","inLanguage":"en-GB","@id":"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/09\/cropped-IMG_E3610-12-Srednie-96x96.png","url":"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/09\/cropped-IMG_E3610-12-Srednie-96x96.png","contentUrl":"https:\/\/www.astor.com.pl\/en\/wp-content\/uploads\/2025\/09\/cropped-IMG_E3610-12-Srednie-96x96.png","caption":"Kamila Piechocka"},"url":"https:\/\/www.astor.com.pl\/en\/author\/kamilapiechocka\/"}]}},"_links":{"self":[{"href":"https:\/\/www.astor.com.pl\/en\/wp-json\/wp\/v2\/posts\/1054","targetHints":{"allow":["GET"]}}],"collection":[{"href":"https:\/\/www.astor.com.pl\/en\/wp-json\/wp\/v2\/posts"}],"about":[{"href":"https:\/\/www.astor.com.pl\/en\/wp-json\/wp\/v2\/types\/post"}],"author":[{"embeddable":true,"href":"https:\/\/www.astor.com.pl\/en\/wp-json\/wp\/v2\/users\/32"}],"replies":[{"embeddable":true,"href":"https:\/\/www.astor.com.pl\/en\/wp-json\/wp\/v2\/comments?post=1054"}],"version-history":[{"count":3,"href":"https:\/\/www.astor.com.pl\/en\/wp-json\/wp\/v2\/posts\/1054\/revisions"}],"predecessor-version":[{"id":1098,"href":"https:\/\/www.astor.com.pl\/en\/wp-json\/wp\/v2\/posts\/1054\/revisions\/1098"}],"wp:featuredmedia":[{"embeddable":true,"href":"https:\/\/www.astor.com.pl\/en\/wp-json\/wp\/v2\/media\/1084"}],"wp:attachment":[{"href":"https:\/\/www.astor.com.pl\/en\/wp-json\/wp\/v2\/media?parent=1054"}],"wp:term":[{"taxonomy":"category","embeddable":true,"href":"https:\/\/www.astor.com.pl\/en\/wp-json\/wp\/v2\/categories?post=1054"},{"taxonomy":"post_tag","embeddable":true,"href":"https:\/\/www.astor.com.pl\/en\/wp-json\/wp\/v2\/tags?post=1054"}],"curies":[{"name":"wp","href":"https:\/\/api.w.org\/{rel}","templated":true}]}}