openshc: a versatile multilegged robot controller

17
OpenSHC: A Versatile Multilegged Robot Controller Benjamin Tam †‡ , Fletcher Talbot , Ryan Steindl , Alberto Elfes , Navinda Kottege Abstract—Multilegged robots have the ability to perform stable locomotion on relatively rough terrain. However, the complexity of legged robots over wheeled or tracked robots make them difficult to control. This paper presents OpenSHC (Open-source Syropod High-level Controller), a versatile high-level controller capable of generating gaits and poses for quasi-static multilegged robots, both simulated and with real hardware implementations. With full Robot Operating System (ROS) integration, the con- troller can be quickly deployed on robots with different actuators and sensor payloads. The flexibility of OpenSHC is demonstrated on the 30 degrees of freedom hexapod Bullet, analysing the energetic performance of various leg configurations, kinematic arrangements and gaits over different locomotion speeds. With OpenSHC being easily configured to different physical and locomotion specifications, a hardware-based parameter space search for optimal locomotion parameters is conducted. The experimental evaluation shows that the mammalian configuration offers lower power consumption across a range of step fre- quencies; with the insectoid configuration providing performance advantages at higher body velocities and increased stability at low step frequencies. OpenSHC is open-source and able to be configured for various number of joints and legs. I. I NTRODUCTION Legged robots have advantages compared to their wheeled and tracked counterparts when navigating in complex terrain. From their ability to traverse discontinuous terrain, climb over obstacles and disturb the terrain minimally, to probing the terrain and manipulating the environment without an additional arm [1], [2]. However, the trade-off of this versatility and mobility is the significant challenges in mechanical and control complexity [3]. The combination of both the robot platform de- sign and the control algorithm determines the performance and effectiveness of the robot. To further research and development of legged robots, the authors present OpenSHC - Open-source Syropod High-level Controller - a versatile controller that is capable of generating statically stable gaits for multilegged robots 1 . It is the result of legged robot locomotion research conducted at CSIRO’s Robotics and Autonomous Systems Group since 2011, with some of the robots running OpenSHC shown in Fig. 1. Using the Robot Operating System (ROS) framework for modularity and easy deployment, OpenSHC is designed to generate foot tip trajectories for a given gait sequence, step clearance, step frequency and input body velocity for many different legged robots with various leg configurations and degrees of freedom. Any legged robot with up to 8 legs that can be specified using Denavit-Hartenberg Robotics and Autonomous Systems Group, Commonwealth Scientific and Industrial Research Organisation (CSIRO), Pullenvale, QLD 4069, Australia. This work was fully funded by the CSIRO. Correspondence should be addressed to [email protected] School of Information Technology and Electrical Engineering, The Uni- versity of Queensland, St. Lucia, QLD 4072, Australia. 1 https://github.com/csiro-robotics/syropod highlevel controller (DH) parameters [4] can be used with OpenSHC. Input sensors such as IMUs and joint effort feedback can be utilised by the controller to provide robust trajectories in inclined and uneven terrain. OpenSHC can also be used in simulation to control robots in rviz and Gazebo simulation environments. This provides a convenient way for roboticists to design legged robots by being able to tune various parameters to fit specific performance criteria. In order to show the capability of OpenSHC, a study on locomotion efficiency of a 30 degrees of freedom (DOF) hexapod robot platform called Bullet in the nature inspired mammalian and insectoid (sprawling-type) configuration is presented. Six legged robots have an advantage over bipeds and quadrupeds when it comes to statically stable locomotion on mild terrain, where the fast tripod gait has an energy efficiency advantage over other gaits [5]. In the mammalian configuration, the legs are below the body, reducing the sup- port polygon while decreasing the power consumption required to support the body. Insectoid configuration places the legs to the side of the body, lowering the centre of mass, increasing locomotion workspace and stability. The different physical and locomotion specifications require unique parameters for con- trol, something OpenSHC allows for easily. The experimental results provide unique insights into the novel parameter space of hardware changes to leg arrangement and configuration; and locomotion changes to step frequency, stride length and gait. The design philosophy and history behind OpenSHC is pre- sented in Section II. The kinematic algorithms in the controller is summarised in Section III. Section IV provides an overview of OpenSHC with details of each sub-component of the system. Section V describes the study of locomotion efficiency with respect to popular leg configurations in literature, while Section VI describes the mechanical specifications of Bullet. Experiments are explained in Section VII with results shown in Section VIII and then discussed in Section IX. Section X concludes the paper and provides areas of focus for the future of OpenSHC. II. DESIGN PHILOSOPHY The design philosophy of OpenSHC was to create a modular controller for research and development on different simulated and real hardware robots without having to redevelop the controller to make each robot walk. A variety of open-source multilegged robot projects ex- ist, each focusing on different challenges and applications. Projects such as OpenRoACH [6], Open Dynamic Robot Initiative [7] and Oncilla [8] have focused on developing a complete robot platform with mechanical and electrical hardware designs, and control software that is tightly coupled to the hardware specifications. OpenSHC on the other hand, arXiv:2006.04424v3 [cs.RO] 19 Oct 2020

Upload: others

Post on 28-Nov-2021

11 views

Category:

Documents


0 download

TRANSCRIPT

Page 1: OpenSHC: A Versatile Multilegged Robot Controller

OpenSHC: A Versatile Multilegged Robot ControllerBenjamin Tam†‡, Fletcher Talbot†, Ryan Steindl†, Alberto Elfes†, Navinda Kottege†

Abstract—Multilegged robots have the ability to perform stablelocomotion on relatively rough terrain. However, the complexityof legged robots over wheeled or tracked robots make themdifficult to control. This paper presents OpenSHC (Open-sourceSyropod High-level Controller), a versatile high-level controllercapable of generating gaits and poses for quasi-static multileggedrobots, both simulated and with real hardware implementations.With full Robot Operating System (ROS) integration, the con-troller can be quickly deployed on robots with different actuatorsand sensor payloads. The flexibility of OpenSHC is demonstratedon the 30 degrees of freedom hexapod Bullet, analysing theenergetic performance of various leg configurations, kinematicarrangements and gaits over different locomotion speeds. WithOpenSHC being easily configured to different physical andlocomotion specifications, a hardware-based parameter spacesearch for optimal locomotion parameters is conducted. Theexperimental evaluation shows that the mammalian configurationoffers lower power consumption across a range of step fre-quencies; with the insectoid configuration providing performanceadvantages at higher body velocities and increased stability atlow step frequencies. OpenSHC is open-source and able to beconfigured for various number of joints and legs.

I. INTRODUCTION

Legged robots have advantages compared to their wheeledand tracked counterparts when navigating in complex terrain.From their ability to traverse discontinuous terrain, climb overobstacles and disturb the terrain minimally, to probing theterrain and manipulating the environment without an additionalarm [1], [2]. However, the trade-off of this versatility andmobility is the significant challenges in mechanical and controlcomplexity [3]. The combination of both the robot platform de-sign and the control algorithm determines the performance andeffectiveness of the robot. To further research and developmentof legged robots, the authors present OpenSHC - Open-sourceSyropod High-level Controller - a versatile controller that iscapable of generating statically stable gaits for multileggedrobots1. It is the result of legged robot locomotion researchconducted at CSIRO’s Robotics and Autonomous SystemsGroup since 2011, with some of the robots running OpenSHCshown in Fig. 1. Using the Robot Operating System (ROS)framework for modularity and easy deployment, OpenSHCis designed to generate foot tip trajectories for a given gaitsequence, step clearance, step frequency and input bodyvelocity for many different legged robots with various legconfigurations and degrees of freedom. Any legged robot withup to 8 legs that can be specified using Denavit-Hartenberg

†Robotics and Autonomous Systems Group, Commonwealth Scientific andIndustrial Research Organisation (CSIRO), Pullenvale, QLD 4069, Australia.This work was fully funded by the CSIRO. Correspondence should beaddressed to [email protected]‡School of Information Technology and Electrical Engineering, The Uni-

versity of Queensland, St. Lucia, QLD 4072, Australia.1https://github.com/csiro-robotics/syropod highlevel controller

(DH) parameters [4] can be used with OpenSHC. Input sensorssuch as IMUs and joint effort feedback can be utilised bythe controller to provide robust trajectories in inclined anduneven terrain. OpenSHC can also be used in simulation tocontrol robots in rviz and Gazebo simulation environments.This provides a convenient way for roboticists to design leggedrobots by being able to tune various parameters to fit specificperformance criteria.

In order to show the capability of OpenSHC, a study onlocomotion efficiency of a 30 degrees of freedom (DOF)hexapod robot platform called Bullet in the nature inspiredmammalian and insectoid (sprawling-type) configuration ispresented. Six legged robots have an advantage over bipedsand quadrupeds when it comes to statically stable locomotionon mild terrain, where the fast tripod gait has an energyefficiency advantage over other gaits [5]. In the mammalianconfiguration, the legs are below the body, reducing the sup-port polygon while decreasing the power consumption requiredto support the body. Insectoid configuration places the legs tothe side of the body, lowering the centre of mass, increasinglocomotion workspace and stability. The different physical andlocomotion specifications require unique parameters for con-trol, something OpenSHC allows for easily. The experimentalresults provide unique insights into the novel parameter spaceof hardware changes to leg arrangement and configuration; andlocomotion changes to step frequency, stride length and gait.

The design philosophy and history behind OpenSHC is pre-sented in Section II. The kinematic algorithms in the controlleris summarised in Section III. Section IV provides an overviewof OpenSHC with details of each sub-component of thesystem. Section V describes the study of locomotion efficiencywith respect to popular leg configurations in literature, whileSection VI describes the mechanical specifications of Bullet.Experiments are explained in Section VII with results shownin Section VIII and then discussed in Section IX. Section Xconcludes the paper and provides areas of focus for the futureof OpenSHC.

II. DESIGN PHILOSOPHY

The design philosophy of OpenSHC was to create a modularcontroller for research and development on different simulatedand real hardware robots without having to redevelop thecontroller to make each robot walk.

A variety of open-source multilegged robot projects ex-ist, each focusing on different challenges and applications.Projects such as OpenRoACH [6], Open Dynamic RobotInitiative [7] and Oncilla [8] have focused on developinga complete robot platform with mechanical and electricalhardware designs, and control software that is tightly coupledto the hardware specifications. OpenSHC on the other hand,

arX

iv:2

006.

0442

4v3

[cs

.RO

] 1

9 O

ct 2

020

Page 2: OpenSHC: A Versatile Multilegged Robot Controller

Fig. 1. A number of different multilegged robots that use OpenSHC, from left to right: Gizmo, Zee, Bullet, MAX and Weaver.

is developed to be applicable to many different legged robotsincluding those in simulation. We also differ from the Phoenix[9] robot control software used to control Trossen RoboticsPhantomX hexapods [10], through full ROS [11] integration,the de facto robotics middleware used by the research com-munity and industry.

OpenSHC is a controller that is not linked to a particularhardware design. That is, OpenSHC allows robot morphol-ogy to be iteratively tested in simulation first, before beingdeployed onto a real system.

Through its full ROS integration, OpenSHC has the abilityto easily interface with simulated robots in Gazebo, the ROScompatible 3D simulation engine, using its Gazebo controlinterface. This allows testing of various features and designparameters in designing a robot without having to go throughhardware based iterations. This is done through the use ofa Universal Robot Description Format (URDF) file whichdescribes the robot model’s links, joints, simulated actuatorsand IMU. The URDF file for the robot platform Bullet, usedin the case study in Section V is provided as part of the suiteof OpenSHC open source software packages. Using OpenSHCto command the joints of a robot model, a user can test customrobot morphologies, gaits, stance positions and various otherparameters to optimise a robot design and test it in a fullphysics simulated environment. In development of the hexapodrobot Bruce, used in the DARPA SubT Challenge [12], initialanalysis of the actuator requirements was undertaken usingOpenSHC and an initial design model of Bruce with simulatedactuators in Gazebo. This analysis involved commanding theinitial Bruce model to run at a variety of velocities and gaits,with a variety of payload weights and recording the simulatedactuator torque requirements. Those requirements were usedto inform the final design of Bruce including morphology andchoice of actuator. Legged robots such as MAX [13], a 2.25 m18 DOF hexapod; Weaver [14] and Bullet [2], both 30 DOFhexapod robots; and Magneto [15], a quadruped with 3 DOF

actuated limbs and 3 DOF compliant magnetic feet have alsobeen extensively simulated using OpenSHC to develop newapplications and functionality (Fig. 2).

The following list highlights some of the key features ofOpenSHC:

• Fully configurable for a variety of platform designs withdiffering physical characteristics, including up to 8 legseach with up to 6 DOF per leg.

• Dynamically switchable gait options with ability to de-sign custom gaits.

• User defined body clearance, step clearance and stepfrequency.

• Manual body posing in 6 DOF.• Manual leg manipulation (legipulation) for up to two legs

simultaneously with toggle of manipulation control ofeither tip position in Cartesian space or direct controlof joint positions (3 DOF legs only).

• Startup direct mode to move foot tip positions linearlyfrom initial position to default walking stance positions.

• Startup sequence mode with full chain ofstartup/shutdown sequences to start from a ‘packed’state and generate a sequence to stand up off the groundinto its default walking stance; and similarly able toshutdown and transition back to a packed state.

• Cruise control mode to set robot velocity as a constantpredefined input velocity or set to the current inputvelocity.

• Auto navigation mode when interfaced with high levelnavigation stack.

• Optional admittance control with dynamic leg stiffnessto ensure leg contact with ground and offer moderatelyrough terrain walking ability.

• Optional IMU body compensation to keep body horizon-tally level at all times, using IMU data.

• Optional inclination compensation which strives to keepbody centre of gravity over the estimated centroid of the

(a) (b) (c) (d)

Fig. 2. OpenSHC used for simulating multilegged robots in Gazebo, from left to right: Bullet, MAX, Weaver and Magneto.

Page 3: OpenSHC: A Versatile Multilegged Robot Controller

support polygon whilst walking on inclined planes.• Optional bespoke automatic body posing system to pose

each robot leg cyclically as defined by auto-pose param-eters.

A variety of research projects conducted in our lab hascontributed and benefited from the controller. Novel function-ality developed on particular robot platforms are generalisedand incrementally added into the controller so other platformscan benefit from the work. Different robot platforms such asMAX, Weaver and Magneto mentioned earlier, have influencedthe design and functionality of the controller. The simplecommand interface for sending velocity control to the systemenabled higher level autonomy to be integrated and testedonto hardware easily. Research in probing for brittle terrain[2], steep terrain ascent [16], adapting robot pose for confinedspaces [17], augmented telepresence for remote inspection [18]and autonomous adaptation of locomotion parameters [19]–[21] have all built upon the OpenSHC framework.

III. KINEMATIC MODEL

In OpenSHC, the robot is represented as a kinematicmodel within the controller using the Denavit-Hartenberg(DH) parameters [4], [22]. This allows for the joint anglesand end effector locations to be easily transformed for forwardkinematics (FK) and inverse kinematics (IK) calculations.The robot’s body frame is represented as pose (obxbybzb),consisting of the body orientation (oroll, opitch, oyaw) and dis-placement in (x, y, z). This robot frame provides the odometryof the robot to a reference map frame (omxmymzm) whichis fixed to the world. The coordinate frames are right-handedwith x forward, y left and z up. Each leg has its own legframe (o1x1y1z1), which is the static offset from the robot’sbody frame origin to the centre of rotation of the first joint ofthat leg, when moving outward from the robot centre. The legframe is used to transform the desired robot body movementto the corresponding leg motions via FK and IK.

The leg number convention used in OpenSHC (shown inFig. 3) follows a clockwise sequence from the front right legas ‘1’ [23]. This convention facilitates arbitrary body designssuch as elongated or axis-symmetric circular bodies [24]. Jointand link names are bio-inspired from insect morphology [25].The links are named coxa, femur, tibia and tarsus and the jointsimmediately before the link is given the same name as the linkfor easy reference (E.g. tibia joint is between the femur andtibia links). Where there are compound joints with multipledegrees of freedom, the individual degrees of freedom is usedas a subscript with the relevant link and joint names (E.g.coxayaw, coxaroll).

A. Forward Kinematics

The specified DH parameters θi, di, ai and αi are therotation around z, translation along z, translation along x and

Coxayaw

FemurTibia

Leg 6 Leg 1

Leg 2

Leg 5

Leg 4 Leg 3

x

yLS

LB/2

LB/2

WB

O

Front (Top view)

Tarsus

Coxaroll

Fig. 3. The kinematic structure of the hexapod Bullet.

rotation around x, respectively [26]. The representation of thecombined homogeneous transform of the parameters becomes:

Hii+1 = Rotz,θi · Transz,di · Transx,ai ·Rotx,αi

=

cθi −sθicαi

sθisαiaicθi

sθi cθicαi −cθisαi aisθi0 sαi cαi di0 0 0 1

(1)

where cx and sx denote cos(x) and sin(x) respectively. Detailson the transformation matrices are provided in Appendix A.For further information about FK, please see [26].

In the notation Hii+1, the superscript denotes the reference

frame (oixiyizi) and the subscript indicates the transformedframe (oi+1xi+1yi+1zi+1). Using Fig. 3 as a 30 DOF hexapodexample, for a leg of the robot the transform from the leg frame(o1x1y1z1) to the end effector (oexeyeze) is given by:

H1e = H1

2 (q1) ·H23 (q2) ·H3

4 (q3) ·H45 (q4) ·H5

e (q5) (2)

where q1, q2, q3, q4 and q5 are the joint angles for the coxayaw,coxaroll, femur, tibia and tarsus joints respectively.

B. Inverse Kinematics

The IK for calculating the desired change in joint angles(∆θ) for a given incremental change in end effector position(∆~s) is calculated using the Jacobian matrix J and theLevenberg-Marquardt method, also known as the damped leastsquares method. Full derivation is provided in Appendix B(based on [27]), with the resultant equation to solve given by:

∆θ = JT(JJT + λ2I

)−1∆~s = Z∆~s (3)

where λ > 0 ∈ R and Z = JT(JJT + λ2I

)−1.

Page 4: OpenSHC: A Versatile Multilegged Robot Controller

Algorithm 1 Locomotion workspace search1: for h ∈ [Hmin, Hmax] do2: for α ∈ [0, 2π] do3: endSearch← false,4: dmax ← 0, Ptarget ← P0

5: while !endSearch do6: Pdesired ← Ptarget7: jsolved ← solveIK(Pdesired)8: for j ∈ jsolved do9: if !withinJointLimits(j) then

10: endSearch← true11: else12: P ← solveFK(j)13: move(foot→ P )14: if |P − Pdesired| > ∆P then15: endSearch← true16: end if17: Ptarget ← increment(Ptarget, α, h)18: dmax ← |Ptarget − P0|19: end if20: end for21: end while22: rα,h = dmax23: end for24: end for

For robots with redundant DOFs, joint position/velocitylimit avoidance (JLA) strategies are used to increase the safeoperation of the joints [28]. A full-time kinematic optimisationmethod of JLA is used to keep the joints away from joint posi-tion and velocity limits as much as possible. The cost functionto minimise uses the p−norm of a vector to approximate thefocusing on the joint which is farthest from its centre, givenby:

Φ (q) =

(n∑i=1

∣∣∣∣Kiiqi − qci

∆qi

∣∣∣∣p) 1

p

(4)

where qci is the centre of the joint range ∆qi for joint i, andK is the matrix for the weights of the joint importance. Forthe optimised solution to the cost function, v is solved by:

v = −∇Φ. (5)

Equation (5) can be optimised for a combined cost functionof position and velocity limits. Combining (3) and (5) ofthe joint limit costing function, the solution for the requiredchange in joint positions qθ is given by:

qθ = Z∆~s + (I − ZJ)v. (6)

The weighting for the preference of joint position limit avoid-ance or joint velocity limit avoidance is able to be customisedwithin OpenSHC.

C. Leg Workspace

The locomotion workspace is pre-computed at system ini-tialisation and used to define the workspace available for

each leg while walking. It is centred around the stance foottip position of each leg and is calculated iteratively throughmoving the desired foot tip along different directions in thexy plane until the kinematics fail. This process is given inAlgorithm 1 which is executed for each foot in the robotmodel. Here, h is the search height, incremented by a prede-fined ∆h height step between minimum and maximum searchheights Hmin and Hmax. The symbol α is the search bearingangle, incremented by a predefined ∆α bearing step. Themaximum distance the foot tip travels from its origin positionis dmax. P0, Ptarget, Pdesired and P are the origin tip position,target tip position, desired tip position and actual tip positionrespectively. The maximum error tolerance between actualand desired tip positions is denoted by ∆P . The functionsolveIK() is the inverse kinematics solver producing jointpositions for a given foot tip position and solveFK() is theforward kinematics solver producing a foot tip position for agiven set of joint angles. jsolved is the set of joint angles fora given leg’s joints for a desired tip position Pdesired. Theworkspace radius for each foot at a given search bearing αand height h is rα,h.

The result is a volumetric workspace, with the differentz-axis height slices forming a polyhedron for each leg. Thetop-down view of these polyhedra for four different robots isillustrated in Fig. 4. A single restricted workspace polygonat the desired body height is called the walkspace. Thewalkspace is constrained to be symmetrical, with the minimumwalkspace from all the legs selected so that the polygon isthe same for each leg. The combination of non-overlappingworkspaces and JLA are used to prevent self-collisions withouta dedicated collision check module. The walkspace is also usedto calculate and limit the stride length for a given desired inputbody velocity. The desired body velocity is passed to the robotfor a given step frequency, with the corresponding stride lengthcalculated to achieve the desired body velocity. The maximumlinear body velocity is thus limited by the walkspace of thelegs. The body velocity calculated by OpenSHC is given by:

vbody =ls × fsβ

(7)

where β is the duty factor defined as β = Tstance/Tstride,the time in stance phase, and the total time of stance andswing phase for the stride time; ls the stride length; and fsthe step frequency. Note that both ls and fs are not fullyindependent, as fs is limited by the maximum joint velocity,which is also affected by the required distance to move fromthe stride length. In reality, the actual velocity is lower due toslippage and other disturbances. However, this is not accountedfor in OpenSHC. Therefore, for accurate robot odometry, anexternal tracking solution is required. More examples of legworkspaces are presented in Section VI-A and Fig. 18.

IV. SYSTEM ARCHITECTURE

The high-level controller consists of multiple modules, andis wrapped as a C++ node within the Robot Operating System(ROS) [11] framework. The utilisation of rostopics and theROS parameter server allows for a common interface to workwith various inputs (for control and sensors) and outputs

Page 5: OpenSHC: A Versatile Multilegged Robot Controller

(a) FrankenX (b) Bullet

(c) Gizmo (d) MAX

Fig. 4. Final result of the locomotion workspace search for four different legged robots visualised in rviz. Top down view: the black outlines represent therobot model, the blue lines show the 3D leg tip workspace limited by morphology and joint limits while the red lines show the restricted planar non-overlappinglocomotion sub-space of the workspace referred to as the walkspace.

(position control of joints), and easy dynamic parameter cus-tomisation. With the integration of Gazebo [29] with ROS,robot algorithms can be tested in simulation before beingdeployed onto hardware. Fig. 5 shows the robot Weaver asa pure kinematic model in rviz, a simulation model in Gazeboand the real robot hardware.

The modules of OpenSHC can be customised via config-uration parameters for each robot platform, with additionalfunctionality modules configurable to be enabled or disableddepending on the scenario. For example, for inclined, uneventerrain, the additional functionality of the different pose gener-ators (Section IV-C) and admittance controller (Section IV-D)can be enabled to increase stability. Fig. 6 shows the simplifiedstructure of OpenSHC with its core functionality. The colouredlines show control flow in typical use. The subsequent figuresbreakout each of the three main controllers in to greater detail.These are the walk controller in Fig. 7, the pose controller inFig. 11 and the robot controller in Fig. 12.

The control inputs received by OpenSHC passes the desiredbody velocity and pose velocity to the walk controller andpose controller whose control flows are shown in green and red

respectively. The tip pose generator combines the tip trajectorywith the body pose and passes it to the robot controller.

This takes the resultant tip pose and calculates the desiredjoint angles. The joint controller calls the IK and FK systemsand performs a final check to constrain the output jointpositions to safe limits. The output joint states of OpenSHCare either sent to the motor controller which controls the servo-motors, or to the control interface of a simulation engine suchas Gazebo. Typical control flow through the robot controlleris shown in blue.

A. Control InputsOpenSHC receives desired body velocities (forward, lateral

and angular) and body posing velocities (6 DOF) via anexternal source. The source can be an operator via a gamepad,tablet, computer, or from an autonomous navigation stack. Theinterface takes in a linear velocity vector along the x, y, zaxes and an angular velocity vector about the x, y, z axes,using the ROS geometry msgs::Twist message as transport.For the walk controller, the system uses the linear x and yvelocities and angular z velocity, with linear z velocity and

Page 6: OpenSHC: A Versatile Multilegged Robot Controller

(a) (b) (c)Fig. 5. The hexapod Weaver in (a) rviz kinematic model, (b) Gazebo simulation and (c) hardware.

angular velocities about x and y being ignored. For the posecontroller, all six velocities are used to pose the robot’s body.

The user is able to select which external source to use,allowing auto navigation or cruise control mode, along withmanual control. Auto navigation requires commands from anautonomous navigation stack that provides obstacles avoidancefunctionality, while cruise control sets the robot’s velocityconstant in the desired velocity generator within the walkcontroller.

B. Walk Controller

The walk controller (Fig. 7) generates the required foottip trajectories and timings from the desired body velocity.Within the walk controller, the gait configuration parametersare converted into timings for each leg in the gait timing

Pose

con

trol

ler

Desired bodyvelocity

Desired posevelocity

Tip trajectorygenerator

Body posegenerator

Desired velocitygenerator

Manual posegenerator

Wal

k co

ntro

ller

Tip posegenerator

Forwardkinematics

Robot controller

Desired joint positions Joint positions

and efforts

Syro

pod

Hig

h-le

vel C

ontr

olle

r

Control inputs

Stride vectorgenerator

Gai

t par

amet

ers

Pose

par

amet

ers

Auto

pos

e pa

ram

eter

s

Wal

k pa

ram

eter

sLe

g pa

ram

eter

s

Ext. targettip pose

Ext. defaulttip pose

Inversekinematics

IMU

Tip state Servomotors Motor controller

Jointcontroller

Admittancecontroller

Fig. 6. OpenSHC’s hierarchical control architecture shown in a simplifiedview containing typically used components only. The coloured arrows showthe flow of information in each controller during typical use. The green,red and blue lines show control flow through the walk controller, the posecontroller and the robot controller respectively.

generator (Section IV-B1) which are then transformed to foottip trajectories in the tip trajectory generator (Section IV-B2).The desired velocity generator fits the body velocity to thewalkspace while the stride vector generator calculates therequired stride length using (7) to achieve the desired velocity.The following subsections describe the gait timing generatorand the tip trajectory generator, two major components of thewalk controller, in detail.

1) Gait Timing Generator: Working along with the stridevector generator to achieve the desired velocity, the gait timinggenerator takes in predefined parameters defining the differentgaits; such as wave, amble, ripple, tripod and the dynamicbipod gaits [5], [30]. The parameters define the ratio betweenthe stance and swing periods of each gait cycle and the phaseoffset between each leg executing the gait cycle, as shown inFig. 8. The timing of these gait cycles and the desired state ofthe leg is sent to the tip trajectory generator which generateseither a swing or stance trajectory based on the current stateof the leg in the gait cycle.

2) Tip Trajectory Generator: The tip trajectory generatorcalculates the foot tip trajectories for the specified gait patternand stride vector. It consists of three 4th order Bezier curves to

Leg stepper

Walk cyclegenerator

Walkspacegenerator

Walk planeestimator

Walk controller

Ext. targettip pose

Ext. defaulttip pose

Gait timinggenerator

Default tip posegenerator G

ait p

aram

s

Phase offset

Stance period

Swing period

Offset multiplier

Wal

k pa

ram

s

Velocity inputmode

Cruise controlparams

Body velocityscaler

Step frequency

Gait type

Stance position

Swing height

Swing width

Step depth

Rough terrainmode

Force normaltouchdown

Tip trajectorygenerator

Desired velocitygenerator

To tip posegenerator

Fromworkspacegenerator

Toworkspace generator

Fromtouchdown detection

To walk plane pose generator

Desired body velocity

Stride vectorgenerator

Fig. 7. Detailed diagram of the walk controller with typical control flowshown in green.

Page 7: OpenSHC: A Versatile Multilegged Robot Controller

Wave Gait (5:1:1)

Offset Multiplier

Gait (Stance:Swing:Base Phase Offset)

Amble Gait (2:1:1)

Ripple Gait (4:2:1)

Tripod Gait (1:1:1)

Bipod Gait (1:2:1)

06

1122031425

02

14

21

35

43

56

011203140516

011223041526

StanceSwingStartup Stance3 Continuing5

0514

213243

56

Leg number (= Leg index) Legend

Fig. 8. Timing for predefined gaits for a hexapod robot.

generate foot positions and velocities over the time period ofthe step cycle. Two Bezier curves control the foot trajectoryacross the primary (first half) and secondary (second half)swing period, and the third Bezier curve controls the stanceperiod. The stance Bezier curve generates foot velocities ratherthan positions using the derivative of the position Bezier curvesused in the swing period. This is to ensure that on-ground footvelocities are guaranteed to match those required to achievethe desired body velocity. Each Bezier curve is defined by 5control points and the following equations:

B(t) = s4P0 + 4ts3P1 + 6s2t2P2 + 4st3P3 + t4P4 (8)

where s = 1− t and t ∈ [0, 1]. The derivative of (8) is givenby:

B′(t) = 4s3(P1 − P0) + 12s2t(P2 − P1)

+ 12t2s(P3 − P2) + 4t3(P4 − P3). (9)

The control points are placed to maximise smoothnessthroughout the step cycle whilst ensuring desired swingcharacteristics, such as step clearance and liftoff/touchdown

Fig. 9. The control points for the three Bezier curves that form the foot tiptrajectory.

Fig. 10. The foot tip trajectory as defined by the three Bezier curves andassociated control points, ensuring desired stride length, step clearance, stepwidth and swing depth.

placement, as well as required ground velocity during stance.Position continuity is ensured between step cycle periods, asshown in Fig. 9, by setting the ‘end’ control points for eachBezier curve at the same location. Similarly, control pointplacement strategies are employed for the remaining controlpoints to ensure velocity and acceleration continuity, produc-ing trajectories which are at least C1 smooth and preferablyC2 smooth within the swing characteristic constraints. Thedesired characteristics of the swing and stance periods haveprecedence over trajectory smoothness. OpenSHC ensures thatthe foot trajectories will always adhere to three requirements:• The foot trajectory during swing is position controlled

to ensure it achieves the defined liftoff and touchdownpositions at the start and end respectively of the primaryand secondary swing Bezier curves.

• The foot trajectory during swing is position controlled toensure it achieves the highest point at the desired stepclearance directly above a defined ‘default’ foot position,i.e. the position of the foot with zero body velocity.

• The foot trajectory during stance is velocity controlledto ensure the required foot velocity is attained as per therequirements of the desired body velocity.

The resultant foot trajectory from the control points isillustrated in Fig. 10.

3) Manual Leg Manipulation: A‘freegait’ module, withinthe walk controller but not shown in Fig. 7 due to beingdecoupled from the typical control flow, allows for leg tip

Page 8: OpenSHC: A Versatile Multilegged Robot Controller

poses to be controlled outside of the cyclic gait. The desiredtip pose of any leg can be controlled by either specifying thevelocity of the leg tip or the actual pose of the leg tip inreference to the leg frame for basic manual leg manipulationtasks (legipulation). The freegait tip pose overrides the tiptrajectory generator output to the tip pose generator. Achievingthe desired tip pose is not guaranteed, subject to IK being ableto solve for valid joint angles for the DOFs available.

C. Pose ControllerThe pose controller (Fig. 11) generates the required tip

pose to achieve the input manual body pose and sensor basedbody pose for safe operation. Changing the body pose fromthe default position and orientation allows the robot to shiftits centre of mass for increased stability on rough terrain.Additionally, sensors mounted onto the robot’s body withlimited field of view can be oriented towards an area ofinterest by changing the body pose. The manual pose generatorreceives the desired body posing velocities from the controlinput and alters the robot’s body pose within the maximumlimits.

The following subsections give details of five main compo-nents of the pose controller: IMU pose generator, inclinationpose generator, current body pose generator, startup/shutdownsequence generator and the tip pose generator.

1) IMU Pose Generator: The IMU pose generator providesfeedback to correct the robot’s body position. The IMU posegenerator makes use of the inertial measurement unit (IMU)to ensure the robot body does not tend towards an unstableposition. As the body experiences changes in roll and pitch,it is posed in opposing roll and pitch axes to correctly alignthe robot frame z-axis parallel to the direction of the gravityvector to keep the body level. This posing controller uses aPID loop to ensure the posing is stable and remains withinpredefined limits.

2) Inclination Pose Generator: During locomotion in heav-ily inclined terrain, if the body is oriented such that correctionfrom posing in roll/pitch cannot stabilise it, then the inclinationpose generator poses the body laterally in the xy plane of therobot frame according to the IMU orientation input. The goalof the system is to centre the vertically projected robot centreof mass into the centre of the support polygon of the robot’sload bearing legs.

3) Current Body Pose Generator: The current body posegenerator adds together the output of several separate bodyposing systems whilst ensuring legs do not exceed the maxi-mum translation and rotation limits of the body. In addition tothe two main body posing sub-systems in Sections IV-C1 andIV-C2, the body pose generator takes input from: the walkplane pose generator which aligns the body to a walkplaneestimate; the auto pose generator which is an automatic userdefined cyclical body pose generator; and the tip aligned posegenerator which shifts the body to allow 3 DOF legs to achievedesired tip orientations upon touchdown. Each body posingsub-system transforms the current body pose generator outputPbody as summarised by:

Pbody = HaliHAIHincHmanPwalk (10)

Leg poser

Pose controller

Tip alignedpose generator

Auto posegenerator

IMU

General tip posetransition generator

Pose

par

ams

IMU posing

Max trans. &rot. velocities

InclinationposingBody

clearanceGravity

aligned tips

Auto posing

Maxtrans./rot.

Startupsequence

Time to start

Tip posegenerator

Inclination posegenerator

Walk planepose generator

Desired pose velocity

Posefrequency

Pose periodlength

Pose periodstart

Pose periodend

RPY amplitude

XYZ amplitude

Gravityamplitude A

uto

pose

par

ams

IMU posegenerator

Manual posegenerator

General joint configtransition generator

Startup/shutdownseq. generator

Current bodypose generator

From walk plane est.

From tip trajectorygenerator

To admittancecontroller

Fig. 11. Detailed diagram of the pose controller showing typical control flowin red.

where Hman, Hinc and Hali are the transformation matricescalculated by manual pose, inclination pose and tip align poserespectively. HAI is either IMU pose or auto pose, as onlyone can be active at a time without interference. Pwalk isthe pose parallel to the walkplane, which is the plane of bestfit from the foot tip contact points. The reference frame ofPwalk is Pdefault, the default pose given by zero translationand identity orientation, except for the body clearance. Theoutput poses of sub-systems that have similar functionalityand incompatible with each other (such as IMU pose or autopose) are removed from the output pose to ensure the systemis not overcompensating for disturbances.

4) Startup/Shutdown Sequence Generator: The sequencegenerator turns a list of joint angles for each joint to achievesequentially, to moving the robot joints to the desired angles.This provides smooth motions from any initial leg positionto the leg positions for stance. The sequence generator alsoallows for the robot to move to a packed state where the legsare tucked in for easy transport. Intermediate steps allows foroverlapping packed legs to be unpacked safely without legcollisions.

5) Tip Pose Generator: The tip pose generator combinesthe desired body pose output of the body pose generator andthe desired tip pose output of the tip trajectory generator tocreate the resultant tip pose for each leg of the robot. Each legtip pose Pleg is referenced from the default body pose framePdefault, the same reference frame used for Pwalk. Thus, theinverse transform is used to transform the leg tip pose P defaultleg

to P bodyleg .The result of each leg’s tip pose generator enables the robot

to enact desired foot tip trajectories for desired walking char-acteristics whilst simultaneously posing the body as desired.This module also ensures tip poses do not exceed the given

Page 9: OpenSHC: A Versatile Multilegged Robot Controller

Leg controllerRobot controller

Touchdowndetection

ForwardKinematics

Leg

para

ms

Admittancecontrol

Integer steptime

Virtual mass

Virtualstiffness

Virtualdamping

Force gain

Touchdown/liftthresholds

Clamp jointpositions

Clamp jointvelocities

Tip forceestimation

InverseKinematics

Workspacegenerator

To motorcontrollerJoint limits

DH parameters

Jointcontroller

Tipcontroller

Linkcontroller

Tip state

From motorcontroller

From motorcontroller

From tip posegenerator

To tip trajectorygenerator

From defaultpose generatorTo walkspacegenerator

Admittancecontroller

Fig. 12. Detailed diagram of the robot controller showing typical control flowin blue.

workspaces for each leg.

D. Robot Controller

The robot controller (Fig. 12) takes the desired poses andtimings of the foot tip and treats it independently for each legvia the leg controllers. It is able to detect foot tip touchdownto stop the leg motors over-torquing and to model the walkplane of the robot. the following subsections describe twoof the main controllers within the leg controllers; admittancecontroller and joint controller.

1) Admittance Controller: The admittance-based leg con-troller is used for rough terrain locomotion and is based on theresearch in [14]. A virtual elastic element is added to the legsto compensate for non-planar foot placements. Joint torquesare mapped to the force at the foot tip using a Jacobian Je asfollows: [

F 2e (t)

M2e (t)

]= (Je(q1, q2, q3, q4, q5)T )−1 ·Mq (11)

where Mq = [M1 M2 M3 M4 M5]T is the vector of jointtorques and q1, q2, q3, q4, q5 are the five joint angles corre-sponding to joints coxayaw, coxaroll femur, tibia and tarsus.F 2e = [Fx Fy Fz]

T and M2e = [Mx My Mz]

T represents the3D force and torque vectors at the foot tip. The admittancecontroller takes the force at the foot tip as an input and outputsa displacement along the z axis. As shown in Fig. 13, a virtualmass mvirt, virtual stiffness cvirt and virtual damping elementbvirt defines the dynamic behaviour along the z axis. Thissecond order system is represented by:

− Fz = mvirt∆zr + bvirt ˙∆zr + cvirt∆zr. (12)

The exerted force and the foot position is adapted by thisvirtual second order mechanical system by reacting to mea-sured foot force. This adapted foot position is zd = zr−∆zr.The displacements ∆xr and ∆yr are set to zero in order torestrict motion in the x and y directions during foot contact.

mvirt

bvirtcvirt

y

z

o

zrzd

¨zr -Fz

Body

Leg

Fig. 13. Admittance control modelled as a mass spring damper mechanicalsystem.

2) Joint Controller: The joint controller handles interactionwith the forward and inverse kinematics systems for every jointin each leg to achieve a desired foot tip pose. It provides legstate and model information for the associated joints for theFK and IK systems to solve (2) and (6) respectively. It alsorestricts any joints to ensure position and velocity limits arenot exceeded. The controller acts with the FK and IK systemsto produce joint commands which, once sent to the motors,will execute the desired pose of the associated foot tip as closeas possible whilst adhering to joint limits.

To convert the desired joint states to movement of themotors, motor interface packages are required. The integrationwith ROS allows for modularity with different servo motorsin the robot hardware. For simulation, a Gazebo model of therobot is controlled through the output of OpenSHC using theROS joint state controller [31].

V. CASE STUDY: OPTIMAL LEGGED LOCOMOTION

The versatility of OpenSHC enables rapid customisation ofthe locomotion parameters to enable different hardware con-figurations to move. The underlying kinematics and trajectoryalgorithms allow various parameters to be optimised. Coupledwith 3D printing for rapid hardware iterations, OpenSHC isused for hardware optimisation of the locomotion parameterspace for a hexapod robot named Bullet, shown in Fig. 14.

The mammalian and insectoid configurations are favouredin nature for different animals with different number oflegs. Predominately, four legged animals have a mammalianconfiguration while six legged animals have an insectoid(arachnid/sprawling-type) configuration. This is reflected inrobotic research as well; mammalian quadruped robots such asANYbotics’ ANYmal [3], Boston Dynamics’ Spot (successorof BigDog [32]), IIT’s HyQ [33] and MIT’s Cheetah 3 [34]have sophisticated controllers capable of dynamic locomotionthat are fast and agile. Insectoid hexapod robots, such as MAX[13], LAURON V [1], DLR-Crawler [35] and SILO6 [36]have been specifically designed for the rough terrain foundin disaster zones, demining areas and complex environments.

Page 10: OpenSHC: A Versatile Multilegged Robot Controller

Fig. 14. Hexapod robot Bullet walking in insectoid (top) and mammalian(bottom) configurations.

For effective locomotion, the mammalian configuration usesa roll-pitch-pitch configuration for its leg joints. The pitchjoints propel the body forwards, while the roll joints are usedfor stability and to aid steering. For insectoid, a yaw-pitch-pitch configuration is used, with the yaw joints mainly usedto propel the body and steer. The pitch joints are required tobear the body weight, even when stationary, consuming moreenergy compared to mammalian configuration.

Research in unique locomotion principles have resulted indesigns of insectoid quadrupeds and mammalian hexapods.The TITAN XIII [37], aimed to use the wider range ofleg motion of an insectoid configuration on a quadruped toachieve energy efficient dynamic walking. MRWALLSPECT-III [38], a climbing robot also used this design to allow fora greater workspace with a low mass. SILO6, a hexapodrobot, has been analysed for energy efficient configurations in[39]. Theoretical and experimental analysis conducted on flatterrain showed that the mammalian configuration in a hexapodproduced a lower power consumption overall, compared withinsectoid. However, SILO6 could not switch between insectoidand mammalian configurations on-the-fly and required manualintervention to mechanically change the leg mounting for thisto be possible. Theoretical analysis of mammalian multileggedrobots is presented in [40], with a set of performance indicesdescribed for optimisation.

Previous works in optimising the locomotion parameterspace have focused on tuning parameters for a single physicalembodiment of the robot. Both learning [41] and non-learning

[20] based methods have been used to optimise for energyefficient locomotion. The focus of this work is to expandthe locomotion parameter search into the unexplored areaof optimising locomotion efficiency for different physicalconfigurations of an over-actuated hexapod robot, along withthe traditional locomotion parameters (step frequency, stridelength and gait type). While the study is not an exhaustivesearch of this space, the hardware-based experimental resultsprovide insight into this unique space.

Bullet was designed to overcome locomotion workspacelimitations of Weaver [14] and is capable of switching betweeninsectoid and mammalian leg configurations. In addition tostatically stable gaits, we also evaluate the performance ofBullet when using the dynamic gait bipod-B introduced in[30]. The bipod-B gait for hexapods provides a fast and energyoptimal gait when foot tips have low traction. With exper-imental results, we show that the mammalian configurationoutperforms the insectoid configuration in energy efficiency atthe expense of stability at low step frequencies and maximumbody velocity.

VI. ROBOT PLATFORM

Bullet is a versatile 30 DOF hexapod robot designed fortraversing rough terrain. Bullet’s body length has been ex-tended compared to Weaver’s, with legs offset further andperpendicular to the body to allow for the legs to be folded be-side the body for a mammalian configuration without limitingthe workspace with self-collisions. Fig. 15 illustrates Bulletin insectoid and mammalian configurations. Bullet is capableof un-tethered remote operation with on-board batteries, com-puter and sensors (described in Table I).

A. Leg Kinematic Arrangement and Workspace

Two different leg kinematic arrangements were designedthrough analysis of workspace and joint limits. The originalkinematic arrangement (arrangement A), first introduced in[20], consists of a yaw-roll-pitch-pitch-pitch kinematic ar-rangement. This arrangement is compared with a new pitch-yaw-pitch-pitch-pitch kinematic arrangement (arrangement B)with extended link lengths. These joints are named coxayaw,coxaroll, femur, tibia and tarsus respectively for the former andcoxapitch, coxayaw, femur, tibia and tarsus respectively for thelatter. Arrangement B increases total leg length from 340 mmto 466 mm and improves joint ranges by up to 20◦through

TABLE IHARDWARE SPECIFICATIONS OF BULLET. A AND B DENOTES THE TWO

KINEMATIC ARRANGEMENTS PRESENTED.

Type Description

General Mass (without battery): 8.41 kg (A), 9.47 kg (B)Mass (with battery): 10.07 kg (A), 11.13 kg (B)Dimensions (Body): LB = 500 mm x WB = 280 mm

Servomotors 30 × Dynamixel MX-106Power supply Motors: 7-cell LiPo battery (25.9 V, 5000 mAh)

Computer: 4-cell LiPo battery (14.8 V, 3300 mAh)Computer Intel i7 NUC PC (16 GB RAM) running ROS on

Ubuntu 16.04Sensors IMU (Microstrain GX5 - 100 Hz)

Arduino based power monitor (90 Hz)

Page 11: OpenSHC: A Versatile Multilegged Robot Controller

H’m

H’i

Insectoid Mammalian

HmHi

Front

Arr

ange

men

t AA

rran

gem

ent B

Fig. 15. Bullet in insectoid and mammalian configuration in kinematic arrangements A and B.

Insectoid leg configurationMammalian leg configuration

Coxayaw joint

Femur joint

Tibia joint

Coxayaw joint

Tarsusjoint

Coxaroll joint

Coxaroll jointTibia joint

Tarsus jointFemur joint

Fig. 16. Bullet’s leg joint configuration in both mammalian (left) and insectoid(right) configurations in kinematic arrangement A.

reduction of self collision. The extended link lengths were setas the minimum length required for the greater joint limits,to lessen the impact of flex and increased motor torques.The change improves the 3D workspace, increases the jointlimits and allows the robot to operate inverted (mirrored aboutthe xy plane). Fig. 16 and 17 illustrates these leg kinematicarrangements in mammalian and insectoid configuration.

Fig. 18 illustrates the different workspaces for each leg con-figuration and kinematic arrangement with the values outlinedin Table II. The workspace area is calculated per leg and thestride length is taken as the forwards (robot’s x-axis) distanceof the workspace assuming forward motion.

Insectoid leg configurationMammalian leg configuration

Coxayaw joint

Femur joint

Tibia joint

Coxayaw joint

Tarsus joint

Coxapitch joint

Tibia joint

Tarsus joint

Femur joint

Coxapitch joint

Fig. 17. Bullet’s leg joint configuration in both mammalian (left) and insectoid(right) configurations in kinematic arrangement B.

B. Leg Configuration

Bullet’s unique five DOF legs and body shape allows forself-actuated switching of the leg configuration between mam-malian and insectoid without external intervention, different to[39]. In the insectoid configuration, five DOFs are availableto position and orientate the leg tarsus. To solve for the foot

TABLE IICALCULATED WORKSPACE OF DIFFERENT CONFIGURATIONS AND

ARRANGEMENTS.

Config. Arrange. Area (m2) Stride Len. (m)

Mammalian A 0.049 0.207B 0.063 0.210

Insectoid A 0.046 0.287B 0.060 0.348

Page 12: OpenSHC: A Versatile Multilegged Robot Controller

-0.6-0.4-0.2

00.20.40.6

-0.6 -0.4 -0.2 0 0.2 0.4 0.6 -0.6 -0.4 -0.2 0 0.2 0.4 0.6-0.6-0.4-0.2

00.20.40.6

Dis

tanc

e (m

)

Distance (m)In

sect

oid

Mam

mal

ian

Arrangement A Arrangement B

Fig. 18. Calculated workspace for the different configurations and arrange-ments. The rectangle represents the robot body with the robot coordinateframe’s origin at its centre. The red dots represent the foot tip locations.

tip position of the over-actuated leg, an additional constraintis used to solve the inverse kinematics problem. The foottip orientation is constrained to return to the original stanceorientation for consistent foot tip touchdown. During the swingphase, the IK solver is able to utilise all joints for motion,following the algorithms outlined in Section III-B. This isdifferent to [20], where the tarsus and coxaroll joints wereconstrained by the inclination of the robot.

To transform Bullet into the mammalian configuration, thecoxayaw joints are commanded and locked to fixed positionsfor kinematic arrangement A. The direction of the leg ori-entation (either forwards or backwards) is controlled throughthe coxayaw joint rotation. For arrangement A, the resultingfour DOF leg contains the coxaroll joint for direction and thethree pitch (femur, tibia and tarsus) joints for propulsion. Inarrangement B, the coxayaw joint is limited, but not locked.This arrangement utilises the coxayaw joint for direction (bybending the leg inwards or outwards) and coxapitch, femur, tibiaand tarsus joints for propulsion. Similar to the insectoid con-figuration, the leg is over-actuated, with the foot tip orientationconstrained during touch down.

For mammalian configuration in quadrupeds, research hasfound marginal differences in stability depending on theelbows and knees pointing forwards or backwards [42]. Inhexapods, the leg orientation of choice is front leg forwards,and middle and rear legs backwards [39], [43]. This orientationwas implemented on kinematic arrangement A without successon Bullet. This was due to stability issues when walking intripod gait caused by Bullet’s centre of mass and the limitedcalculated leg workspace. The workspace was limited dueto the femur and tibia joints reaching their limits. Throughanalysis of the workspace and stability while walking, the legsbackwards configuration was found to be the most stable for

walking while maximising the workspace that borders with theadjacent legs. Due to the legs bending backwards, the rear twosets of legs were required to be further behind the body to keepthe centre of mass within the support polygon, causing theasymmetrical leg positions for the mammalian configurationas shown in Fig. 18. Leg arrangement B follows the sameorientation for consistency.

C. Parameter Space

The parameter search space is defined by physical andlocomotion parameters. The physical parameters encapsulatethe leg configuration (mammalian and insectoid) and kine-matic arrangement (A: yaw-roll-pitch-pitch-pitch or B: pitch-yaw-pitch-pitch-pitch). From these physical parameters, thelocomotion parameters of: gait type, step frequency and stridelength are optimised. These parameters are summarised as:

Π = C ×A×G× Ls × Fs (13)

where the sets C = {Mammalian, Insectoid}, A ={A, B}, G = {tripod, bipod}, Ls = {60, 75, 90, 100}as a percentage of maximum stride length and Fs ={0.4, 0.6, 0.8, 1.0, 1.2, 1.4, 1.6, 1.8, 2.0, 2.2} in Hz. The searchfor the optimal combinations were limited to motions that weresafe for the robot, with some combinations not investigated.

VII. EXPERIMENTS

The performance of Bullet was tested across flat terrain toevaluate the effectiveness of the different configurations.

A. Performance Metrics

The power consumption and joint torques were compared instance (standing stationary) and while walking on flat terrain.The dimensionless energetic cost of transport (CoT ) is aperformance metric used to compare locomotion of animals[44] and also wheeled and legged robots [14], [37], [45]. Theoverall cost of transport (CoT ) over a travelled distance isgiven by:

CoT =

1n

n∑i=1

UiIi

mg∆x∆t

(14)

where U is the power supply voltage (V ), I is the instanta-neous power supply current draw (A), n is the total numberof data points, m is the mass (kg), g is the gravitationalacceleration (ms−2) and ∆t is the time needed in secondsto travel distance ∆x (m). Herein, CoT refers to the overallCoT .

The CoT depends on the velocity of the robot [44], whereconsumption is high at low and high speeds, with a local mini-mum value at a particular speed. The desired body velocity forthe controller is governed by (7), assuming perfect conditions,ignoring slippage, robot model tolerances, leg link flex andmotor errors. Thus, a higher desired velocity can be achievedthrough increasing either the step frequency or stride lengthparameter. To account for non-perfect conditions, the bodyvelocity was tracked externally for CoT calculations.

Page 13: OpenSHC: A Versatile Multilegged Robot Controller

To evaluate the effectiveness of the different configurations,the tripod gait, known for its stability and speed, was comparedbetween mammalian and insectoid at different speeds. Otherstatically stable gaits such as amble, wave or ripple were nottested as previous works have shown tripod is optimal on flatterrain. The insectoid bipod-B gait [30], was also compared.OpenSHC allows for parameters, listed in Table III, to be set.These values were heuristically tuned to optimise for energyefficiency using the rules listed in [39].

B. Experimental Setup

The power consumption and energy efficiency for the dif-ferent leg configurations were tested in four scenarios. Thesescenarios break down the different terms that contribute topower consumption and are:• SA - Power consumed in stance elevated in the air (robot

lifted up, no ground contact),• WA - Power consumed walking elevated in the air (robot

lifted up, no ground contact),• SG - Power consumed in stance on the ground, and• WG - Power consumed walking on the ground.

These scenarios follow the experiments set out in [39] where:scenario SA (stance air) provides the power consumed bythe motor power circuitry; scenario WA (walk air) providesthe power consumed for leg movements; scenario SG (stanceground) for supporting the robot’s body weight; and scenarioWG (walk ground) for overall power consumption. The robotwas elevated on a stand with legs in mid-air for scenarios SAand WA. The robot was placed on the ground and walked oncein place to measure the power consumption when stationaryin scenario SG. Bullet was analysed traversing flat ground inscenario WG. A flat, slightly inclined 3 m straight track wasmarked for the robot. For the calculation of CoT in (14),power consumption (P = UI) was logged with a powermonitor at 90 Hz and velocity v was measured with a totalstation (Leica TS12) at approximately 4 Hz. The CoT isbased on the power draw of the motors, including mechanicalenergy, heat dissipation and friction, while the computer andsensors power consumption is assumed to be constant acrossthe different configurations and arrangements, and are poweredon a separate power supply. Bullet was tested using a tetherto an external power supply and control computer, with theinternal batteries and computer on-board to simulate the realweight of the robot. The power supply was set at 25 V andthe control computer is an i7 laptop with 8 GB of RAM.

VIII. RESULTS

The metric used to compare scenarios SA, WA and SG ispower consumption with results outlined in Table IV, while

TABLE IIICONTROLLER PARAMETERS FOR INSECTOID AND MAMMALIAN

Config. Arrange. Stride height (m) Body height (m)

Mammalian A 0.12 Hm = 0.30B 0.08 H′m = 0.30

Insectoid A 0.15 Hi = 0.20B 0.10 H′i = 0.25

0.4 0.6 0.8 1 1.2 1.4 0.4 0.6 0.8 1 1.2 1.40.02

0.04

0.06

0.08

0.1

0.12

0.14

0.16

Step Frequency (Hz) Step Frequency (Hz)

Avg.

vel

ocity

(ms-1

)

6

8

10

12

14

16

18

20

CoT

100%90%75%

100%90%75%

Stride length Stride length

(a) (b)

Fig. 19. CoT for arrangement A mammalian tripod gait at various stepfrequencies and stride lengths.

CoT is used for scenario WG. The power consumed in stancefor both kinematic arrangements of mammalian is lower thantheir corresponding insectoid. This validates the theory ofless torque on the motors with the legs underneath as theforce vectors act through the motor shaft. The difference inpower between the air and ground shows the additional powerrequired to support the robot’s weight. While arrangement Aconsumes less power than B in stance while in the air, onthe ground arrangement B consumes less. This suggests thatthe joints in arrangement B require less torque to keep thebody up. The walking in air comparison is for step frequency1 Hz at 100% stride length. The results show the insectoidbipod consuming the highest amount of energy for leg motion,while in mammalian, arrangement B uses less power thanarrangement A.

An analysis of arrangement A mammalian configurationat different step frequency and stride length compared tothe CoT is shown in Fig. 19. The stride length, given as apercentage of the available locomotion workspace, shows thata higher length for a given step frequency is more energyefficient. The minimum value at 1 Hz shows the optimal stepfrequency and stride length for energy efficient locomotion.An increase of step frequency above 1 Hz increases the powerusage greatly. At a step frequency of 1.4 Hz, the foot tipsslipped considerably, causing the tracked velocity to be lowerthan that of step frequency 1.2 Hz; even though the desiredbody velocity is greater.

The insectoid configuration was analysed with the tripod

TABLE IVAVERAGE POWER CONSUMPTION (W)

Config. Arrange. Gait Stance air Walk air Stance ground

Mammalian A Tripod 27.7 51.0 48.6B Tripod 30.4 47.1 46.7

Insectoid A Tripod 30.4 61.9 58.3A Bipod 30.4 72.3 58.3B Tripod 31.1 62.9 56.0

Page 14: OpenSHC: A Versatile Multilegged Robot Controller

0.05

0.1

0.15

0.2

0.25

0.3

0.35

0.4

0.45

Avg.

Vel

ocity

(ms-1

)

Step Frequency (Hz)

2

4

6

8

10

12

14C

oT

0.6 1 1.8 2.21.4Step Frequency (Hz)

0.6 1 1.8 2.21.4

Mammalian TripodInsectoid BipodInsectoid Tripod

Mammalian TripodInsectoid BipodInsectoid Tripod

(a) (b)

Fig. 20. CoT for insectoid bipod and tripod, and mammalian tripod gait atvarious step frequencies at 100% stride length for arrangement A.

1 1.5 2 2.5 3 3.5 4Step Frequency (Hz)

CoT

4

6

8

10

12

14

16

18

20

22

0.05

0.1

0.15

0.2

0.25

0.3

0.35

Avg.

Vel

ocity

(ms-1

)

1 1.5 2 2.5 3 3.5 4Step Frequency (Hz)

Mammalian 100%Insectoid 60%Insectoid 100%

Mammalian 100%Insectoid 60%Insectoid 100%

Stride length

Stride length

(a) (b)

Fig. 21. CoT for mammalian and insectoid tripod gait at various stepfrequencies and stride lengths for arrangement B. Insectoid stride length 60%was limited to be the same metric length as mammalian 100% stride length.

and bipod gait in arrangement A. A stride length of 100%was used in tests as results in mammalian showed a stridelength of 100% is the most efficient across all step frequenciestested. Fig. 20 compares the CoT and average velocity as thestep frequency increases. Similar to mammalian configuration,tripod gait has a minimum CoT , occurring at 1.8 Hz. Anincrease of step frequency above 1.8 Hz increases the CoT .The bipod gait does not exhibit this minimum, instead havingdiminished reductions for step frequencies about 2 Hz. Thebipod gait performed equally or better than the tripod gaitat all step frequencies. For step frequencies above 2 Hz, bothinsectoid gaits cause considerable clamping of the joint anglesby OpenSHC. This caused body instability and the foot tip tono longer track the trajectory. Step frequencies above 2.2 Hzwere not tested to prevent hardware damage.

For arrangement B, tests were conducted to compare

-0.5

0

0.5

Cox

a yaw

Mammalian Tripod

-1

0

1

Cox

a roll

-5

0

5

Fem

ur

-5

0

5

Tibi

a

-5

0

5

Tars

us

-5

0

5Insectoid Tripod

-5

0

5

-5

0

5

-5

0

5

-5

0

5

-5

0

5Insectoid Bipod

-5

0

5

-5

0

5

-5

0

5

-5

0

5

(a) (b) (c)

Fig. 22. Velocity (rads−1) profile of the joints in the front right leg forarrangement A. The solid blue line denotes a step frequency of 1 Hz at100% stride length. The dotted red line denotes the maximum step frequencyat 100% stride length for each configuration (1.4 Hz, 2.2 Hz and 2.2 Hzrespectively). The x-axis denotes two periods of the step frequency at 1 Hz.

the mammalian and insectoid configuration given the sameworkspace across various step frequencies. The mammalianconfiguration was tested at 100% stride length. This wascompared with insectoid at 60.27% of its maximum workspaceto have the same metric stride length as mammalian. Fig. 21outlines the CoT and average velocity as the step frequencyincreases. Insectoid at 100% stride length was included forcomparison. At low step frequencies, the mammalian con-figuration was observed to have body oscillation and foottip slip, resulting in the high CoT . At step frequency 2 Hzand above, where the body oscillations were minimal, themammalian configuration has comparable or better perfor-mance than both insectoid stride lengths. Given the samestride length, mammalian configuration consistently has alower CoT than insectoid across step frequencies above 2 Hz(Fig. 21a). However, the actual robot velocity is consistentlylower than insectoid (Fig. 21b). The local minimum value forCoT occurs at step frequency 3 Hz for both configurations,suggesting it is the step frequency and stride length that affectsthe local minimum CoT and not the leg configuration.

The comparison of 100% stride length between the twoconfigurations show the advantages and disadvantages of each.The insectoid configuration can achieve a higher maximumvelocity at lower step frequencies and is also more stable.However, it causes the joints to reach limits at a lower fre-quency (observed at 2 Hz compared to mammalian at 3.5 Hz).The drop in velocity in insectoid at high step frequenciesis caused by joint velocity clamping while executing thedesired controller trajectory. As the weight of the robot isconstant across the different trials, the CoT is effectively therelative power required to traverse a set distance, and can bedirectly used to compare energy efficiency of the differentconfigurations.

Page 15: OpenSHC: A Versatile Multilegged Robot Controller

-0.2

0

0.2Mammalian Tripod

-0.2

0

0.2

-1

0

1

-1

0

1

-0.5

0

0.5

-1

0

1Insectoid Tripod

-0.5

0

0.5

-1

0

1

-1

0

1

-1

0

1

-1

0

1Insectoid Bipod

-1

0

1

-1

0

1

-1

0

1

-1

0

1

Cox

a yaw

Cox

a roll

Fem

urTi

bia

Tars

us

(a) (b) (c)

Fig. 23. Load profile (dimensionless) of the joints in the front right legfor arrangement A. The solid blue line denotes a step frequency of 1 Hz at100% stride length. The dotted red line denotes the maximum step frequencyat 100% stride length for each configuration (1.4 Hz, 2.2 Hz and 2.2 Hzrespectively). The x-axis denotes two periods of the step frequency at 1 Hz.

IX. DISCUSSION

The use of an over-actuated leg to achieve switching be-tween mammalian and insectoid configuration was exploredfor the first time. To achieve the mammalian configuration,the coxayaw joint motors were commanded to set positions,with torque holding those positions. This was reflected by thesmall velocity and load on the joint illustrated in Fig. 22aand 23a respectively. Comparing the load on the joints acrossthe different gaits (Fig. 23 blue line), the mammalian tripodgait had lower torques on all the joints. The results for thestance power consumption experiments (scenarios SA and SG)confirmed the theory in [46] and also the experimental data in[39] with the mammalian configuration using less energy thaninsectoid when standing.

Arrangement A mammalian configuration consumed lesspower than insectoid in stance (SG) and leg movement (WG),but was not the most efficient in locomotion due to thesmaller locomotion workspace and joint angle limits. Therobot in insectoid configuration was capable of covering largerdistances in the same number of steps, negating the higherpower required to support its weight and for locomotion. Withthe joint limit improvements in arrangement B, the mammalianconfiguration achieved lower CoT than insectoid. The mam-malian configuration was optimal if the least amount of powerto traverse an area is required. Arrangement B mammalian didnot reach joint velocity limits until higher step frequencies asthe pitch-yaw-pitch-pitch-pitch kinematic arrangement affordsfour pitch joints to propel the robot forwards.

Analysis of the insectoid tripod and bipod gait showed alower CoT for the latter. Although the bipod gait consumedmore power, it was able to walk faster than tripod at thesame step frequency. This supports the hardware experimentsconducted in [30]. On average, the bipod gait was 30% fasterthan the equivalent tripod gait, similar to the 25% increasereported in [30]. Between the two arrangements and across

different gaits, arrangement A bipod had the lowest CoT . Theresults showed improved locomotion efficiency is achievablewith OpenSHC, providing direction for future works in theabsence of sophisticated dynamic controllers.

The versatility of OpenSHC was highlighted on experimentsconducted on a versatile hexapod capable of switching be-tween different configurations. We show that this switchingability has advantages over traditional fixed configurationrobots in autonomous navigation of terrain. When traversingmild terrains, where stability and speed is of less importance,the mammalian configuration consumes less power. For terrainor scenarios where stability or speed is required (such asrough terrain or speed critical tasks), the robot can morphinto insectoid configuration. This ability to select the optimalconfiguration provides the robot an advantage on locomotionefficiency for real world scenarios. Having an over-actuatedleg design allows for the additional ability to selectively useparticular motors for locomotion and to switch between thedifferent configurations. While a single DOF is unused inthe mammalian configuration, setting the motor to a fixedposition results in the robot using less power overall. Theresults highlight the advantages of a versatile hexapod runningOpenSHC, capable of selecting between configurations andstep frequencies, based on energy efficiency (mammalian) orstability and speed (insectoid) requirements.

X. CONCLUSIONS

This paper presented OpenSHC, a versatile controller ca-pable of generating smooth trajectories for quasi-static leggedrobots. With many customisable parameters, the controller canbe configured for new robot platforms with various physicalcharacteristics. OpenSHC provides the building blocks toextend the capabilities of multilegged robot platforms througha modular hierarchical architecture. By providing ‘out of thebox’ functionality for locomotion in mild to rough terrain,OpenSHC allows researchers to focus on higher level ar-eas such as autonomy or application specific motions thatwould increase the versatility of legged robots. With addi-tional sensors, robots would be capable of traversing in morecomplex and confined environments, something that quasi-static multilegged platforms would be ideal for. Another areaof research that OpenSHC supports is in leg manipulation.For robot platforms with greater than 3 DOF legs, OpenSHCallows for manual position and orientation control of thefoot tip, allowing attachments such as grippers to manipulatethe environment. Additionally, with its seamless integrationwith rviz and Gazebo simulation environments, OpenSHCprovides a way for researchers to design, test and optimisenew legged robots in simulation and make informed choicesabout hardware based on application requirements.

APPENDIX AFORWARD KINEMATICS DERIVATION

The DH parameters θi, di, ai and αi used in (1) from Sec-tion III-A are represented as transformation matrices using theshorthand cx and sx to denote cos(x) and sin(x) respectively.

Page 16: OpenSHC: A Versatile Multilegged Robot Controller

The transformation matrix for the DH parameter θi is givenby:

Rotz,θi =

cθi −sθi 0 0sθi cθi 0 00 0 1 00 0 0 1

(15)

The transformation matrix for the DH parameter di is givenby:

Transz,di =

1 0 0 00 1 0 00 0 1 di0 0 0 1

(16)

The transformation matrix for the DH parameter ai is givenby:

Transx,ai =

1 0 0 ai0 1 0 00 0 1 00 0 0 1

(17)

The transformation matrix for the DH parameter αi is givenby:

Rotx,αi=

1 0 0 00 cαi −sαi 00 sαi

cαi0

0 0 0 1

(18)

APPENDIX BINVERSE KINEMATICS DERIVATION

The IK for the change in joint angles for a given desired endeffector position is calculated using the Jacobian. The Jacobianmatrix J is defined as:

J (θ) =

(∂si∂θj

)i,j

(19)

where si is the end effector of the link which is affected byjoint θj . The linear velocity component of the Jacobian canbe calculated by:

∂si∂θj

= vj ×(si − pj

)(20)

where vj is the unit vector along the current axis of rotationand pj is the position of the jth joint. For incremental iterationsof the end effector, a change in the end effector can beapproximated by:

∆~s ≈ J∆θ. (21)

Thus, using the Levenberg-Marquardt method, also knownas the damped least squares method, ∆θ can be solved by:

∆θ ≈ JT(JJT + λ2I

)−1∆~s (22)

where λ > 0 ∈ R. Using this approximation and compactnotation, we get:

∆θ = JT(JJT + λ2I

)−1∆~s = Z∆~s (23)

where Z = JT(JJT + λ2I

)−1.

The cost function to minimise for JLA in OpenSHC isrepresented by:

Φ (q) =

n∑i=1

[qi − qci

∆qi

]2

(24)

where qci is the centre of the joint range ∆qi for joint i.

ACKNOWLEDGEMENT

The authors would like to thank Oshada Jayasinghe,Marisa Bucolo, James Brett, Isuru Kalhara, Eranda Tennakoon,Thomas Molnar, Benjamin Wilson, Thomas Lowe, and DavidRytz for their support during this project.

REFERENCES

[1] A. Roennau, G. Heppner, M. Nowicki, and R. Dillmann, “LAURONV: A versatile six-legged walking robot with advanced maneuverabil-ity,” in IEEE/ASME International Conference on Advanced IntelligentMechatronics, July 2014, pp. 82–87.

[2] E. Tennakoon, T. Peynot, J. Roberts, and N. Kottege, “Probe-before-stepwalking strategy for multi-legged robots on terrain with risk of collapse,”in IEEE International Conference on Robotics and Automation, 2020.

[3] M. Hutter, C. Gehring, D. Jud, A. Lauber, C. D. Bellicoso, V. Tsounis,J. Hwangbo, K. Bodie, P. Fankhauser, M. Bloesch, R. Diethelm, S. Bach-mann, A. Melzer, and M. Hoepflinger, “ANYmal - a highly mobile anddynamic quadrupedal robot,” in IEEE/RSJ International Conference onIntelligent Robots and Systems, 2016, pp. 38–44.

[4] R. Hartenberg and J. Danavit, Kinematic Synthesis of Linkages. NewYork, NY: McGraw-Hill, 1964.

[5] N. Kottege, C. Parkinson, P. Moghadam, A. Elfes, and S. P. N. Singh,“Energetics-informed hexapod gait transitions across terrains,” in IEEEInternational Conference on Robotics and Automation, 2015, pp. 5140–5147.

[6] L. Wang, Y. Yang, G. Correa, K. Karydis, and R. S. Fearing, “Open-roach: A durable open-source hexapedal platform with onboard robotoperating system (ros),” in 2019 International Conference on Roboticsand Automation (ICRA), 2019, pp. 9466–9472.

[7] F. Grimminger, A. Meduri, M. Khadiv, J. Viereck, M. Wuthrich,M. Naveau, V. Berenz, S. Heim, F. Widmaier, T. Flayols, J. Fiene,A. Badri-Sprowitz, and L. Righetti, “An open torque-controlled modularrobot architecture for legged locomotion research,” IEEE Robotics andAutomation Letters, vol. 5, no. 2, pp. 3650–3657, 2020.

[8] A. T. Sprowitz, A. Tuleu, M. Ajallooeian, M. Vespignani, R. Mockel,P. Eckert, M. D’Haene, J. Degrave, A. Nordmann, B. Schrauwen,J. Steil, and A. J. Ijspeert, “Oncilla robot: A versatile open-source quadruped research robot with compliant pantograph legs,”Frontiers in Robotics and AI, vol. 5, p. 67, 2018. [Online]. Available:https://www.frontiersin.org/article/10.3389/frobt.2018.00067

[9] J. Janssen, K. Halvorsen, K. Eckhardt, M. E. Ferguson, andB. Porter, “Phantom phoenix,” 2018. [Online]. Available: https://github.com/KurtE/Phantom Phoenix

[10] Trossen Robotics, “PhantomX hexapod robot kits,”2020. [Online]. Available: https://www.trossenrobotics.com/Quadruped-Robot-Hexapod-Robot-Kits.aspx

[11] M. Quigley, K. Conley, B. Gerkey, J. Faust, T. Foote, J. Leibs,R. Wheeler, and A. Y. Ng, “ROS: an open-source robot operatingsystem,” in IEEE ICRA workshop on open source software, vol. 3, 2009,p. 5.

[12] R. Steindl, T. Molnar, F. Talbot, N. Hudson, B. Tam, S. Murrell, andN. Kottege, “Bruce - design and development of a dynamic hexapodrobot,” in Australasian Conference on Robotics and Automation (toappear), 2020.

[13] A. Elfes, R. Steindl, F. Talbot, F. Kendoul, P. Sikka, T. Lowe, N. Kottege,M. Bjelonic, R. Dungavell, T. Bandyopadhyay, M. Hoerger, B. Tam,and D. Rytz, “The multilegged autonomous explorer (MAX),” in IEEEInternational Conference on Robotics and Automation, 2017, pp. 1050–1057.

[14] M. Bjelonic, N. Kottege, and P. Beckerle, “Proprioceptive control ofan over-actuated hexapod robot in unstructured terrain,” in IEEE/RSJInternational Conference on Intelligent Robots and Systems, 2016, pp.2042–2049.

Page 17: OpenSHC: A Versatile Multilegged Robot Controller

[15] T. Bandyopadhyay, R. Steindl, F. Talbot, N. Kottege, R. Dungavell,B. Wood, J. Barker, K. Hoehn, and A. Elfes, “Magneto: A versatilemulti-limbed inspection robot,” in IEEE/RSJ International Conferenceon Intelligent Robots and Systems, 2018, pp. 2253–2260.

[16] T. Molnar, R. Steindl, N. Kottege, F. Talbot, and A. Elfes, “Steep terrainascension controller for hexapod robots,” in Australasian Conference onRobotics and Automation, 2017.

[17] R. Buchanan, T. Bandyopadhyay, M. Bjelonic, L. Wellhausen, M. Hutter,and N. Kottege, “Walking Posture Adaptation for Legged Robot Naviga-tion in Confined Spaces,” IEEE Robotics and Automation Letters, vol. 4,no. 2, pp. 2148–2155, 2019.

[18] B. Tam, N. Kottege, and B. Kusy, “Augmented telepresence for remoteinspection with legged robots,” in Australasian Conference on Roboticsand Automation, 2017.

[19] T. Homberger, M. Bjelonic, N. Kottege, and P. V. K. Borges, “Terrain-dependent motion adaptation for hexapod robots,” in InternationalSymposium on Experimental Robotics, 2016.

[20] M. Bjelonic, T. Homberger, N. Kottege, P. Borges, M. Chli, and P. Beck-erle, “Autonomous navigation of hexapod robots with vision-basedcontroller adaptation,” in IEEE International Conference on Roboticsand Automation, May 2017, pp. 5561–5568.

[21] M. Bjelonic, N. Kottege, T. Homberger, P. Borges, P. Beckerle, andM. Chli, “Weaver: Hexapod robot for autonomous navigation on unstruc-tured terrain,” Journal of Field Robotics, vol. 35, no. 7, pp. 1063–1079,2018.

[22] M. W. Spong, S. Hutchinson, and M. Vidyasagar, Robot Modeling andControl. Hoboken, NJ: Wiley, 2006.

[23] P. S. Dominik Belter, “A biologically inspired approach to feasiblegait learning for a hexapod robot,” International Journal of AppliedMathematics and Computer Science, vol. 20, no. 1, pp. 69–84, 2010.

[24] D. C. Clemente, Gait optimization for multi-legged walking robots, withapplication to a lunar hexapod. Stanford University, California, CA,USA, 2011.

[25] G. M. Nelson, R. D. Quinn, R. J. Bachmann, W. C. Flannigan, R. E.Ritzmann, and J. T. Watson, “Design and simulation of a cockroach-like hexapod robot,” in IEEE International Conference on Robotics andAutomation, vol. 2, 1997, pp. 1106–1111.

[26] K. J. Waldron and J. Schmiedeler, “Kinematics,” in Springer Handbookof Robotics, B. Siciliano and O. Khatib, Eds. Cham, Switzerland:Springer International Publishing, 2016, pp. 11–36.

[27] S. R. Buss, “Introduction to Inverse Kinematics with Jacobian Transpose,Pseudoinverse and Damped Least Squares methods,” University ofCalifornia, San Diego, Department of Mathematics, Tech. Rep., 2004.

[28] F. Fahimi, “Redundant Manipulators,” in Autonomous Robots: Modeling,Path Planning, and Control, F. Fahimi, Ed. Boston, MA: Springer US,2009, pp. 1–36.

[29] N. Koenig and A. Howard, “Design and use paradigms for Gazebo, anopen-source multi-robot simulator,” in IEEE/RSJ International Confer-ence on Intelligent Robots and Systems, vol. 3, 2004, pp. 2149–2154.

[30] P. Ramdya, R. Thandiackal, R. Cherney, T. Asselborn, R. Benton,A. J. Ijspeert, and D. Floreano, “Climbing favours the tripod gait overalternative faster insect gaits,” Nature Communications, vol. 8, p. 14494,2017.

[31] S. Chitta, E. Marder-Eppstein, W. Meeussen, V. Pradeep,A. Rodrıguez Tsouroukdissian, J. Bohren, D. Coleman, B. Magyar,

G. Raiola, M. Ludtke, and E. Fernandez Perdomo, “ros control: Ageneric and simple control framework for ROS,” The Journal of OpenSource Software, 2017.

[32] M. Raibert, K. Blankespoor, G. Nelson, and R. Playter, “BigDog,the Rough-Terrain Quadruped Robot,” in IFAC Proceedings Volumes,vol. 41, no. 2. Elsevier, 2008, pp. 10 822–10 825.

[33] C. Semini, V. Barasuol, J. Goldsmith, M. Frigerio, M. Focchi, Y. Gao,and D. G. Caldwell, “Design of the Hydraulically Actuated, Torque-Controlled Quadruped Robot HyQ2max,” IEEE/ASME Transactions onMechatronics, vol. 22, no. 2, 2017.

[34] G. Bledt, M. J. Powell, B. Katz, J. D. Carlo, P. M. Wensing, and S. Kim,“MIT Cheetah 3: Design and control of a robust, dynamic quadrupedrobot,” in IEEE/RSJ International Conference on Intelligent Robots andSystems, 2018, pp. 2245–2252.

[35] M. Gorner, T. Wimbock, A. Baumann, M. Fuchs, T. Bahls, M. Greben-stein, C. Borst, J. Butterfass, and G. Hirzinger, “The DLR-Crawler: Atestbed for actively compliant hexapod walking based on the fingersof DLR-Hand II,” in IEEE/RSJ International Conference on IntelligentRobots and Systems, 2008, pp. 1525–1531.

[36] P. G. de Santos, J. Cobano, E. Garcia, J. Estremera, and M. Armada,“A six-legged robot-based system for humanitarian demining missions,”Mechatronics, vol. 17, no. 8, pp. 417 – 430, 2007.

[37] S. Kitano, S. Hirose, A. Horigome, and G. Endo, “Titan-xiii: sprawling-type quadruped robot with ability of fast and energy-efficient walking,”ROBOMECH Journal, vol. 3, no. 1, p. 8, 2016.

[38] T. Kang, H. Kim, T. Son, and H. Choi, “Design of quadruped walkingand climbing robot,” in IEEE/RSJ International Conference on Intelli-gent Robots and Systems, vol. 1, 2003, pp. 619–624 vol.1.

[39] D. Sanz-Merodio, E. Garcia, and P. G. de Santos, “Analyzing energy-efficient configurations in hexapod robots for demining applications,”Industrial Robot: An International Journal, vol. 39, no. 4, pp. 357–364,2012.

[40] M. F. Silva and J. A. T. Machado, “Kinematic and dynamic performanceanalysis of artificial legged systems,” Robotica, vol. 26, no. 1, p. 19–39,2008.

[41] E. Heijmink, A. Radulescu, B. Ponton, V. Barasuol, D. G. Caldwell, andC. Semini, “Learning optimal gait parameters and impedance profiles forlegged locomotion,” IEEE-RAS International Conference on HumanoidRobotics, pp. 339–346, 2017.

[42] S. Meek, J. Kim, and M. Anderson, “Stability of a trotting quadrupedrobot with passive, underactuated legs,” in IEEE International Confer-ence on Robotics and Automation, 2008, pp. 347–351.

[43] B. Jin, L. j. Zhao, J. L. Zhang, C. Chen, and S. Hu, “Design of the controlsystem for a hexapod walking robot,” in International Conference onDigital Manufacturing Automation, 2011, pp. 401–404.

[44] V. A. Tucker, “The energetic cost of moving about: walking and runningare extremely inefficient forms of locomotion. much greater efficiencyis achieved by birds, fish and bicyclists,” American Scientist, vol. 63,no. 4, pp. 413–419, 1975.

[45] S. Seok, A. Wang, M. Y. Chuah, D. Otten, J. Lang, and S. Kim, “Designprinciples for highly efficient quadrupeds and implementation on themit cheetah robot,” in IEEE International Conference on Robotics andAutomation, 2013, pp. 3307–3312.

[46] D. J. Todd, Walking Machines: An Introduction to Legged Robots.Boston, MA: Springer US, 1985.