{"id":206,"date":"2013-07-13T15:33:55","date_gmt":"2013-07-13T19:33:55","guid":{"rendered":"http:\/\/projectsofdan.com\/?p=206"},"modified":"2013-07-13T22:01:05","modified_gmt":"2013-07-14T02:01:05","slug":"phase-4-foot-trajectory-planning-and-gait-sequencing-part-ii","status":"publish","type":"post","link":"https:\/\/projectsofdan.com\/?p=206","title":{"rendered":"Phase 4: Foot Trajectory Planning and Gait Sequencing Part II"},"content":{"rendered":"<p>In the <a title=\"Phase 4: Foot Trajectory Planning and Gait Sequencing, i.e., Walking Part I\" href=\"http:\/\/projectsofdan.com\/?p=165\">previous post<\/a>, I went over my initial linear approach to stepping and why it didn&#8217;t work out so well. This post outlines my current method which is working much better.<\/p>\n<p>The new method uses a sinusoidal &#8220;arch&#8221; shaped step in the ZX plane. This also works out well since a single sine function can cover the raise and lower part of the step in one time segment. By using a sinusoidal function for the front-to-back stepping in the X direction as well, i could cut the number of case in half to just two. The final benefit is that it produces a very smooth and natural motion with the smooth curves and foot speeds. Here&#8217;s what step code looks like:<\/p>\n<pre class=\"brush: cpp; title: ; notranslate\" title=\"\">\r\nswitch (caseStep&#x5B;legNum]){\r\n\r\n                case 1: \/\/forward raise and lower\r\n\r\n                    leg&#x5B;legNum].footPos.x = -amplitudeX*cos(M_PI*tick\/numTicks);\r\n                    leg&#x5B;legNum].footPos.y = -amplitudeY*cos(M_PI*tick\/numTicks);\r\n                    leg&#x5B;legNum].footPos.z = -abs(amplitudeZ)*sin(M_PI*tick\/numTicks);\r\n\r\n                    if( tick &gt;= numTicks-1 ) caseStep&#x5B;legNum] = 2;\r\n                    break;\r\n\r\n                case 2: \/\/ pull back\r\n\r\n                    leg&#x5B;legNum].footPos.x = amplitudeX*cos(M_PI*tick\/numTicks);\r\n                    leg&#x5B;legNum].footPos.y = amplitudeY*cos(M_PI*tick\/numTicks);\r\n                    leg&#x5B;legNum].footPos.z = 0;\r\n\r\n                    if( tick &gt;= numTicks-1 ) caseStep&#x5B;legNum] = 1;\r\n                    break;\r\n\r\n          }\/\/ end of case statement\r\n<\/pre>\n<p>As you noticed, the sequencing itself is carried out by the case statement block. They key to the sequencing is in the caseStep[] array. The array has six elements, one for each leg. The variable defines at which case each leg begins. For a tripod gait, the front right leg (#1), rear right (#3), and middle left (#5) leg all start at the first case and step together. The other legs start 180deg off which is the second case. So for my <a title=\"Phase 4: Foot Trajectory Planning and Gait Sequencing Part I\" href=\"http:\/\/projectsofdan.com\/?p=165\">prior<\/a> four-case linear &#8220;triangle&#8221; step function, caseStep[] is defined as {1,3,1,3,1,3}. For the new two-case &#8220;sine&#8221; step function, caseStep[] is defined as {1,2,1,2,1,2}.<\/p>\n<p>Each case statement increments caseStep[] to the next case in order to advance to the next portion of the foot step. The final code looks like:<\/p>\n<pre class=\"brush: cpp; title: ; notranslate\" title=\"\">\r\n\/*************************************************\r\n  tripodGaitSine()\r\n\r\n**************************************************\/\r\nvoid tripodGaitSine(){\r\n\r\n    float sinRotZ, cosRotZ;\r\n    int totalX, totalY;\r\n    float rotSpeedOffsetX&#x5B;6], rotSpeedOffsetY&#x5B;6];\r\n    float amplitudeX, amplitudeY, amplitudeZ;\r\n    int duration;\r\n    int numTicks;\r\n    int speedX, speedY, speedR;\r\n\r\n    if( (abs(commanderInput.Xspeed) &gt; 5) || (abs(commanderInput.Yspeed) &gt; 5) || (abs(commanderInput.Rspeed) &gt; 5 ) ){\r\n\r\n        duration = 500;                               \/\/duration of one step cycle (ms)\r\n        numTicks = round(duration \/ SERVO_UPDATE_PERIOD \/ 2.0); \/\/total ticks divided into the two cases\r\n\r\n        speedX = 180*commanderInput.Xspeed\/127;        \/\/180mm\/s top speed for 180mmm stride in one sec\r\n        speedY = 180*commanderInput.Yspeed\/127;        \/\/180mm\/s top speed\r\n        speedR = 40*commanderInput.Rspeed\/127;         \/\/40deg\/s top rotation speed\r\n\r\n        sinRotZ = sin(radians(speedR));\r\n        cosRotZ = cos(radians(speedR));\r\n\r\n        for( int legNum=0; legNum&lt;6; legNum++){                        totalX = leg&#x5B;legNum].initialFootPos.x + leg&#x5B;legNum].legBasePos.x;              totalY = leg&#x5B;legNum].initialFootPos.y + leg&#x5B;legNum].legBasePos.y;                          rotSpeedOffsetX&#x5B;legNum] = totalY*sinRotZ + totalX*cosRotZ - totalX;               rotSpeedOffsetY&#x5B;legNum] = totalY*cosRotZ - totalX*sinRotZ - totalY;                           if( abs(speedX + rotSpeedOffsetX&#x5B;legNum]) &gt; abs(speedY + rotSpeedOffsetY&#x5B;legNum]) )\r\n\t\tamplitudeZ = ((speedX + rotSpeedOffsetX&#x5B;legNum])*duration\/3000.0);\r\n            else\r\n\t\tamplitudeZ = ((speedY + rotSpeedOffsetY&#x5B;legNum])*duration\/3000.0);\r\n\r\n            amplitudeX = ((speedX + rotSpeedOffsetX&#x5B;legNum])*duration\/2000.0);\r\n            amplitudeY = ((speedY + rotSpeedOffsetY&#x5B;legNum])*duration\/2000.0);\r\n\r\n            switch (caseStep&#x5B;legNum]){\r\n\r\n                case 1: \/\/forward raise and lower\r\n\r\n                    leg&#x5B;legNum].footPos.x = -amplitudeX*cos(M_PI*tick\/numTicks);\r\n                    leg&#x5B;legNum].footPos.y = -amplitudeY*cos(M_PI*tick\/numTicks);\r\n                    leg&#x5B;legNum].footPos.z = -abs(amplitudeZ)*sin(M_PI*tick\/numTicks);\r\n\r\n                    if( tick &gt;= numTicks-1 ) caseStep&#x5B;legNum] = 2;\r\n                    break;\r\n\r\n                case 2: \/\/ pull back\r\n\r\n                    leg&#x5B;legNum].footPos.x = amplitudeX*cos(M_PI*tick\/numTicks);\r\n                    leg&#x5B;legNum].footPos.y = amplitudeY*cos(M_PI*tick\/numTicks);\r\n                    leg&#x5B;legNum].footPos.z = 0;\r\n\r\n                    if( tick &gt;= numTicks-1 ) caseStep&#x5B;legNum] = 1;\r\n                    break;\r\n\r\n          }\/\/ end of case statement\r\n\r\n        }\/\/ end of loop over legs\r\n        if (tick &lt; numTicks-1) tick++;\r\n        else tick = 0;\r\n\r\n    }\/\/end if joystick active\r\n\r\n}\r\n<\/pre>\n<p>I think it needs a little fine tuning of the speeds and step durations, but its essentially done. B.E.T.H. is now fully mobile!<\/p>\n<p>Check out where this all <a title=\"The Game Plan for B.E.T.H.\" href=\"http:\/\/projectsofdan.com\/?p=32\">began<\/a>.<\/p>\n","protected":false},"excerpt":{"rendered":"<p>In the previous post, I went over my initial linear approach to stepping and why it didn&#8217;t work out so well. This post outlines my current method which is working much better. The new method uses a sinusoidal &#8220;arch&#8221; shaped step in the ZX plane. This also works out well since a single sine function [&hellip;]<\/p>\n","protected":false},"author":1,"featured_media":0,"comment_status":"open","ping_status":"open","sticky":false,"template":"","format":"standard","meta":{"footnotes":""},"categories":[4],"tags":[5,7,34,13,6],"class_list":["post-206","post","type-post","status-publish","format-standard","hentry","category-b-e-t-h","tag-hexapod","tag-phantomx","tag-b-e-t-h","tag-raspberry-pi","tag-robot"],"_links":{"self":[{"href":"https:\/\/projectsofdan.com\/index.php?rest_route=\/wp\/v2\/posts\/206","targetHints":{"allow":["GET"]}}],"collection":[{"href":"https:\/\/projectsofdan.com\/index.php?rest_route=\/wp\/v2\/posts"}],"about":[{"href":"https:\/\/projectsofdan.com\/index.php?rest_route=\/wp\/v2\/types\/post"}],"author":[{"embeddable":true,"href":"https:\/\/projectsofdan.com\/index.php?rest_route=\/wp\/v2\/users\/1"}],"replies":[{"embeddable":true,"href":"https:\/\/projectsofdan.com\/index.php?rest_route=%2Fwp%2Fv2%2Fcomments&post=206"}],"version-history":[{"count":11,"href":"https:\/\/projectsofdan.com\/index.php?rest_route=\/wp\/v2\/posts\/206\/revisions"}],"predecessor-version":[{"id":255,"href":"https:\/\/projectsofdan.com\/index.php?rest_route=\/wp\/v2\/posts\/206\/revisions\/255"}],"wp:attachment":[{"href":"https:\/\/projectsofdan.com\/index.php?rest_route=%2Fwp%2Fv2%2Fmedia&parent=206"}],"wp:term":[{"taxonomy":"category","embeddable":true,"href":"https:\/\/projectsofdan.com\/index.php?rest_route=%2Fwp%2Fv2%2Fcategories&post=206"},{"taxonomy":"post_tag","embeddable":true,"href":"https:\/\/projectsofdan.com\/index.php?rest_route=%2Fwp%2Fv2%2Ftags&post=206"}],"curies":[{"name":"wp","href":"https:\/\/api.w.org\/{rel}","templated":true}]}}