8
MECHANICAL SIMULATION OF THE EXOMARS ROVER USING SICONOS IN 3DROV Vincent Acary 1 , Maurice Br´ emond 1 , Konstantinos Kapellos 2 , Jan Michalczyk 1 , and Roger Pissard-Gibollet 1 1 INRIA Grenoble, Inovall´ ee, 38330 Montbonnot, France, email:fi[email protected] 2 TRASYS Space, Terhulpsesteenweg 6c, 1560 Hoeilaart, Belgium. email:fi[email protected] ABSTRACT This paper presents ongoing work at INRIA in collabo- ration with TRASYS on the mechanical modelling and simulation of planetary rovers. We focus our presenta- tion on an specific approach used the INRIA SICONOS software. This approach [2] based on the nonsmooth Me- chanics theory is dedicated to the modeling and the sim- ulation of multi–body systems with joints, hard contacts, Coulomb’s friction and impacts. In addition, software in- tegration aspects are considered defining and implement- ing generic software interfaces between SICONOS and external 3D tools. The approach is applied to the rover planetary operations enhancing the fidelity and the gener- icity of the ExoMars existing rover mechanical models used in the TRASYS 3DROV [24] simulator. Key words: Siconos; 3DRov; contact; impact; Coulomb’s friction; nonsmooth dynamics ; numerical simulation;. 1. INTRODUCTION This paper presents ongoing work at INRIA in collabo- ration with TRASYS on the mechanical modelling and simulation of planetary rovers. The first aim is to use the modeling and the simulation features of the INRIA SICONOS software dedicated to nonsmooth dynamical systems [2] into a specific rover simulator developed by TRASYS, 3DROV. In this particular application, we fo- cus our work on the simulation of multi-body systems that undergo unilateral contact, friction and impact with its environment. We present a open–source software code, able to deal with idealized contact interaction based on unilateral (rigid) contact, 3D Coulomb friction and impacts. Using such a software into an overall simu- lation tool as 3DROV may help a lot in designing the control law for locomotion and simulating the global be- havior of the rover. In addition, software integration as- pects are considered defining and implementing generic software interfaces between SICONOS and external 3D tools. The approach is applied to the rover planetary op- erations enhancing the fidelity and the genericity of the ExoMars existing rover mechanical models used in the TRASYS 3DROV [24] simulator. The ultimate objective of this work is to integrate SICONOS and 3DROV from the rover mechanical modelling phase to the rover motion simulation and 3D Visualization. Outline. In Section 2, we briefly review the literature on the modeling and simulation of rovers. In Section 3, we present the main features of Siconos with a brief ex- planation of the interest of using a nonsmooth approach for contact and friction simulations. Section 3 ends with several stand-alone experiments of obstacle avoidance and traction performance. In Section 4, the TRASYS 3DROV [24] rover planetary operations simulator is pre- sented. Section 5 concludes the paper. 2. STATE OF THE ART The design of the rover chassis and the study of the lo- comotion have already been the object of a lot of ef- forts from several teams in the NASA’s Mars Exploration Rovers(MER) project and in the ESA’s ExoMars project. The main subjects of interests are the static stability of the rover over steep slopes and the kinematic studies for obstacle avoidance which asks for specific requirements on the geometry of the suspension. The traction perfor- mance, which demands for minimal friction requirements has also been extensively studied. To achieve these vari- ous goals, designers have worked mainly on the suspen- sion systems and the design of the wheels in order to ob- tain a good trade-off of performances over various ter- rains from soft soils (sands, fine granular materials) to rigid surfaces (rocks, coarse granular materials). For an overview of these efforts, we refer to [17, 19, 20, 28] and [22] for a survey. Physical–based modeling and simulation of planetary rovers is an integral part of planning, testing and de- sign of robotic planetary missions. Therefore, most of these studies have been based on simulation soft- ware codes, which are for most of them overall simula- tion tools containing the simulation of multi-body sys- tems in their environment (mainly with the interaction wheel/terrain), the simulation of the control systems, the hardware in the loop system and the 3D Visualiza- tion rendering and animations systems. One of the first piece of software is ROAMS (Rover Analysis, Modeling and Simulation) developed at the Jet Propulsion Labora- tory (JPL) for the NASA’s MER project. It is based on the DSHELL/DARTS software[32, 15, 14, 8] and offers functionalities for the overall mission simulation with embedded software ans operator–in–the–loop simulator. A particular focus is made on the wheel/terrain interac- tion by integrating on the Bekker model [6, 7] and its extensions. On the ESA’s side, a lot of efforts has been done to develop robust and efficient simulation tools.

MECHANICAL SIMULATION OF THE EXOMARS ROVER USING …robotics.estec.esa.int/ASTRA/Astra2013/Papers/Acary_2824437.pdf · body systems with contact and friction, all the previous software

  • Upload
    others

  • View
    5

  • Download
    0

Embed Size (px)

Citation preview

Page 1: MECHANICAL SIMULATION OF THE EXOMARS ROVER USING …robotics.estec.esa.int/ASTRA/Astra2013/Papers/Acary_2824437.pdf · body systems with contact and friction, all the previous software

MECHANICAL SIMULATION OF THE EXOMARS ROVER USING SICONOS IN 3DROV

Vincent Acary1, Maurice Bremond1, Konstantinos Kapellos2, Jan Michalczyk1, and Roger Pissard-Gibollet1

1INRIA Grenoble, Inovallee, 38330 Montbonnot, France, email:[email protected] Space, Terhulpsesteenweg 6c, 1560 Hoeilaart, Belgium. email:[email protected]

ABSTRACT

This paper presents ongoing work at INRIA in collabo-ration with TRASYS on the mechanical modelling andsimulation of planetary rovers. We focus our presenta-tion on an specific approach used the INRIA SICONOSsoftware. This approach [2] based on the nonsmooth Me-chanics theory is dedicated to the modeling and the sim-ulation of multi–body systems with joints, hard contacts,Coulomb’s friction and impacts. In addition, software in-tegration aspects are considered defining and implement-ing generic software interfaces between SICONOS andexternal 3D tools. The approach is applied to the roverplanetary operations enhancing the fidelity and the gener-icity of the ExoMars existing rover mechanical modelsused in the TRASYS 3DROV [24] simulator.

Key words: Siconos; 3DRov; contact; impact;Coulomb’s friction; nonsmooth dynamics ; numericalsimulation;.

1. INTRODUCTION

This paper presents ongoing work at INRIA in collabo-ration with TRASYS on the mechanical modelling andsimulation of planetary rovers. The first aim is to usethe modeling and the simulation features of the INRIASICONOS software dedicated to nonsmooth dynamicalsystems [2] into a specific rover simulator developed byTRASYS, 3DROV. In this particular application, we fo-cus our work on the simulation of multi-body systemsthat undergo unilateral contact, friction and impact withits environment. We present a open–source softwarecode, able to deal with idealized contact interaction basedon unilateral (rigid) contact, 3D Coulomb friction andimpacts. Using such a software into an overall simu-lation tool as 3DROV may help a lot in designing thecontrol law for locomotion and simulating the global be-havior of the rover. In addition, software integration as-pects are considered defining and implementing genericsoftware interfaces between SICONOS and external 3Dtools. The approach is applied to the rover planetary op-erations enhancing the fidelity and the genericity of theExoMars existing rover mechanical models used in theTRASYS 3DROV [24] simulator. The ultimate objectiveof this work is to integrate SICONOS and 3DROV fromthe rover mechanical modelling phase to the rover motionsimulation and 3D Visualization.

Outline. In Section 2, we briefly review the literatureon the modeling and simulation of rovers. In Section 3,we present the main features of Siconos with a brief ex-planation of the interest of using a nonsmooth approachfor contact and friction simulations. Section 3 ends withseveral stand-alone experiments of obstacle avoidanceand traction performance. In Section 4, the TRASYS3DROV [24] rover planetary operations simulator is pre-sented. Section 5 concludes the paper.

2. STATE OF THE ART

The design of the rover chassis and the study of the lo-comotion have already been the object of a lot of ef-forts from several teams in the NASA’s Mars ExplorationRovers(MER) project and in the ESA’s ExoMars project.The main subjects of interests are the static stability ofthe rover over steep slopes and the kinematic studies forobstacle avoidance which asks for specific requirementson the geometry of the suspension. The traction perfor-mance, which demands for minimal friction requirementshas also been extensively studied. To achieve these vari-ous goals, designers have worked mainly on the suspen-sion systems and the design of the wheels in order to ob-tain a good trade-off of performances over various ter-rains from soft soils (sands, fine granular materials) torigid surfaces (rocks, coarse granular materials). For anoverview of these efforts, we refer to [17, 19, 20, 28] and[22] for a survey.

Physical–based modeling and simulation of planetaryrovers is an integral part of planning, testing and de-sign of robotic planetary missions. Therefore, mostof these studies have been based on simulation soft-ware codes, which are for most of them overall simula-tion tools containing the simulation of multi-body sys-tems in their environment (mainly with the interactionwheel/terrain), the simulation of the control systems,the hardware in the loop system and the 3D Visualiza-tion rendering and animations systems. One of the firstpiece of software is ROAMS (Rover Analysis, Modelingand Simulation) developed at the Jet Propulsion Labora-tory (JPL) for the NASA’s MER project. It is based onthe DSHELL/DARTS software[32, 15, 14, 8] and offersfunctionalities for the overall mission simulation withembedded software ans operator–in–the–loop simulator.A particular focus is made on the wheel/terrain interac-tion by integrating on the Bekker model [6, 7] and itsextensions. On the ESA’s side, a lot of efforts has beendone to develop robust and efficient simulation tools.

Page 2: MECHANICAL SIMULATION OF THE EXOMARS ROVER USING …robotics.estec.esa.int/ASTRA/Astra2013/Papers/Acary_2824437.pdf · body systems with contact and friction, all the previous software

Among others, this work includes RCAST developed byMDA and the Dalhousie University in Canada. It is asimulator including 3D simulation of multibody systemsfrom CAD model (SolidWorks and Pro/E) based on Mat-lab/Simulink toolbox, SimMechanics. It includes richwheel-soil interaction models developed in a Simulink S-Function blockset based on the AESCO Soft Soil TireModel (AS2TM enhancement of the Bekker model)[5]and a standard control system based on sensors andactuators in Simulink. This software is embedded inthe Simulink’s Virtual Reality Toolbox. Other simula-tors dedicated for the simulation of general multibodysystems have also been used like SIMPACK at DLR[11, 19, 20] with an elasto–plastic models with dampingof soils and experimental fitting of parameters or COS-MOS/Motion in [21] in the context of Rover MobilityPerformance Evaluation Tool (RMPET). Recently, an ef-fort has also been done in the framework of 20sim to de-velop a software for the port–based modeling and simu-lation of the rover on rough terrain [23, 30]. One of themain advantage of the port–based and the bond graph ap-proach is the possibility to integrate in the same modelmulti–physical systems and the control systems.

Concerning the specific aspect of the simulation of multi–body systems with contact and friction, all the previoussoftware codes share a wheel/terrain modeling based onsome extensions of the Bekker model. From the compu-tational point of view, this model is very convenient be-cause it is sufficiently regular to simulate it with any kindof numerical time integration solvers. If Bekker’s modelis well–suited for soft soil/wheel interactions, it may bemore debatable for rigid soils like rocks or coarse gran-ular materials. In this latter case, the stiffness constantsat contact that models the rigid contact of the wheel andthe rocks drastically increase and put the standard simula-tion tools in troubles. This disadvantage in terms of mod-eling and simulation efficiency can be overcome with anonsmooth approach as we propose in Siconos. Dealingwith inequality constraints to model extremely stiff con-tacts rather than using large stiffness constants ensuresthe stability and the efficiency of the solvers. Further-more, the choice of complex models at contact with a lotof parameters can be difficult to use on varying and un-even terrain. The problem of identifying parameters andtheir large variability can be a drawback for designingand testing robust control laws and performing realisticpredictive simulations. Most of the time, when stiff con-tact are involved, the respect of impenetrability betweenbodies, the ideal modeling of threshold and multi–valuedeffects of the Coulomb friction and the coverage of thedissipation effects with an impact law are sufficient andeven more robust for the simulation and the analysis ofmechanical systems.

In the more general framework of the simulation ofrobotic systems, commercial pieces of software have alsobeen used to simulate systems in the framework of theExoMars project. One can cite MapleSim1 and Math-works SimMechanics2. Other tools as Modelica (ve-hicle dynamics or 3D mechanical systems toolboxes)3

1http://www.maplesoft.com/products/maplesim2http://www.mathworks.fr/products/

simmechanics/3https://www.modelica.org/libraries_old/

ModelicaMultiBody

or Microsoft Robotics developer Studio4 may also beused, although as far as we know no publication is avail-able. In 3DRov [24] or more general robotic simulatorlike Gazebo5, physical engines that come from computergames and animation like ODE, Bullet6 or PhysX7 arealso used for mainly two reasons. The first one is thatODE and Bullet are open source software codes and thesecond one is that they deal with an apparent simplicitywith idealized contact and friction models. Nevertheless,since these software codes are developed for the simu-lation of large scenes of objects for videos games, therealistic Physics and Mechanics are sometimes sacrificedfor some performance reasons. For instance, part of thedynamical system may be artificially frozen and the mod-eling of Coulomb’s friction is often not realistic.

3. SICONOS

SICONOS is an Open Source scientific software primar-ily targeted at modeling and simulating nonsmooth dy-namical systems in the most generic sense. In partic-ular, it can deal with the following systems: mechan-ical systems (Rigid body or solid) with unilateral con-tact and Coulomb friction as we find in nonsmooth me-chanics, contact dynamics or Granular material, switchedElectrical Circuit such as electrical circuits with idealand piecewise linear components Power converter, Rec-tifier, Phase-locked loop (PLL) or Analog-to-digital con-verter, sliding mode control systems. Other applicationsare found in Systems and Control (hybrid systems, differ-ential inclusions, optimal control with state constraints),Optimization (Complementarity systems and Variationalinequalities), Biology (Gene regulatory network), FluidMechanics and Computer graphics. The software isbased on 4 main components :1. SICONOS/NUMERICS (C API). Collection of low-level algorithms for solving basic Algebra and optimiza-tion problems arising in the simulation of nonsmoothdynamical systems: Linear complementarity problems(LCP) Mixed linear complementarity problems (MLCP)Nonlinear complementarity problems (NCP) Quadraticprogramming problems (QP) Friction-contact problems(2D or 3D) (Second-order cone programming (SOCP))Primal or Dual Relay problems2. SICONOS/KERNEL. C++ API that allows one tomodel and simulate nonsmooth dynamical systems. itcontains : Dynamical systems classes (first order one,Lagrangian systems, Newton-Euler systems) and non-smooth laws (complementarity, Relay, FrictionContact,impact)3. SICONOS/MECHANICS This component is a modelingtoolbox for multi-body systems based on external colli-sion and geometry libraries.4. SICONOS/FRONT-END generated python bindings forNumerics, Kernel and Mechanics, with a special supportfor Siconos data structures.

Nonsmooth Mechanics at a glance In this section, werecall the main ingredients of the nonsmooth mechanics

4http://www.microsoft.com/robotics5http://gazebosim.org6http://bulletphysics.org7https://developer.nvidia.com/technologies/

physx

Page 3: MECHANICAL SIMULATION OF THE EXOMARS ROVER USING …robotics.estec.esa.int/ASTRA/Astra2013/Papers/Acary_2824437.pdf · body systems with contact and friction, all the previous software

approach for the modeling and the simulation of mechan-ical systems with contact and friction. For more details,we refer to [2]. Let us start with the following Lagrangianformulation of the equations of motion

q = v, (1a)

M(q)v +N(q, v) + F (t, q, v, u) = G>(q)λ, (1b)

u = d(t, q, v, u, λ), (1c)

gk(q) = 0, k ∈ E (1d)

gk(q) ≥ 0, λk ≥ 0, λkgk(q) = 0 k ∈ I,(1e)

where q(t) ∈ IRn is a set of coordinates that gives ina unique way the configuration of the system. The vec-tor v(t) ∈ IRn describes the velocity. The matrix M ∈IRn×n is a symmetric, positive and (semi-)definite matrixrepresenting the inertia. The vector of gyroscopic effectsis denoted as N ∈ IRn. The vector of forces F ∈ IRn

applied to the system includes the internal and externalforces and the effect of the vector u ∈ IRnu which mightbe considered as a control input vector. The dynamicsof this control can be described by another first order dy-namical system (1c). The sets E ⊂ IN and I ⊂ IN arethe index sets of bilateral constraints (E stand for equal-ities) and of unilateral constraints (I stand for inequal-ities), respectively. The matrix G(q) = ∇>q g(q) is theJacobian of the constraints. The condition (1e) is called acomplementarity condition, or equivalently the Signorinicondition. It can be equivalently written as

0 ≤ gk(q) ⊥ λk ≥ 0 for all k ∈ I. (2)

This condition models the basic unilateral contact condi-tion. The complementarity comes from the fact that thereaction force at contact represented by λ can only actwhen the contact is closed, that is when gk(q) = 0.

In order to complete the model at contact, let us introducethe local contact variables. Usual kinematic relations be-tween the local velocity Uk ∈ IR3 at one contact k andthe generalized variables, and by duality, the generalizedforces r due to contact forces Rk ∈ IR3 give

Uk(t) = Gk(q)q = Gk(q)v, r = G>k (q)Rk. (3)

Let us drop the subscript k to lighten the notation. By in-troducing a local frame at contact (N,T,S) where N is aunit normal vector, we can decompose the local variablesas U = UN N + UT, UT ∈ IR2, R = RN N + RT, RT ∈IR2. The Lagrangian dynamics in (1) is usually not sosmooth. If the normal relative velocity at contact UN(t

?)is positive when the bodies hit at time t?, in other words,when an impact occurs, a velocity jump must occur tosatisfy the constraints after t? and an impact law has tobe added. Let us simply choose the Newton impact law

U+N (t?) = −eU−N (t?), for all t such that g(q(t?)) = 0.

(4)By formulating the unilateral contact in terms of localvariables at contact we get the impact law at the veloc-ity level

if gN∆= g(q) ≤ 0, then 0 ≤ U+

N + eU−N ⊥ RN ≥ 0.(5)

Coulomb’s friction can be expressed in a disjunctive formas

if gN ≤ 0,

if UT = 0 then R ∈ C

if UT 6= 0 then R ∈ ∂C, and it existsa ≥ 0 such that RT = −aUT

(6)where C is the Coulomb friction cone, C = {R, |‖RT‖ ≤ µRN} with µ the coefficient of friction.Coulomb’s friction can also be formulated compactlyas a complementarity condition on second–order conesas [2, 4, 3]

−U ∆= −

[UN + µ‖UT‖UT

]and C∗ ∈ U ⊥ R ∈ C (7)

where C∗ is the dual cone of C [27].

Interest of the nonsmooth mechanics approach.Here are listed the main interests of using an approachbased on nonsmooth Mechanics when we want to dealwith multi–body systems with unilateral contacts, fric-tion and impacts:1. The use of complementarity formulation allows us todeal with hard contacts in a very efficient way avoidingthe issues related to the time–integration of stiff prob-lems. When we want to simulate contacts on hard sur-faces, avoiding deep inter–penetrations obliges to uselarge stiffness parameters in a standard approach. Thisis overcame in the presented approach.2. Nonsmooth contact laws are based on few parame-ters (coefficient of restitution and friction). Contact pa-rameters are often very difficult to measure and have agreat variability. Proposing contact laws with few pa-rameters that represents the main effects at contact (inter–penetrability avoidance, friction with real sticking phaseand plastic dissipation) provides the user with robust sim-ulation tools in view of Control applications. Further-more, nonsmooth contact laws can be easily extended totake into account more enhanced effects such as stiffness,damping or cohesion[2]. For soft–soil simulation, piece-wise continuous Bekker model could be implemented inthis context.3. The associated simulation methods are proven to beefficient on a large number of applications from mediumto large scale multi–body systems [26]. Granular mate-rials with large number of contacts points (between 104

and 106) can be simulated with such algorithms.4.

Such an approach has been proved to be robust andefficient on several important industrial applications.Siconos is for instance used for more than 5 years ina strong collaboration between Schneider Electric andINRIA for the virtual prototyping of the mechanismsof circuit breakers [1]. The robustness with respect tocontact parameters and the efficiency of the simulationthat avoids problems due to stiffness provides SchneiderElectric with a robust predictive tool for new designs.This numerical methods are also the object of a closedcollaboration with ANSYS for the rigid body dynamicstoolbox[12].

Architecture and implementation The developmentteam focused on the development of the simulation and

Page 4: MECHANICAL SIMULATION OF THE EXOMARS ROVER USING …robotics.estec.esa.int/ASTRA/Astra2013/Papers/Acary_2824437.pdf · body systems with contact and friction, all the previous software

modeling tools which are as most as possible reusable fordifferent scientific contexts.

Any specific pre/post-processing tools has been devel-oped. Dynamical systems and interactions (unilateralconstraints) classes provided by Siconos/Kernel may beconfigured with the help of plugins or by class derivation.For high–level applications SICONOS relies on externalsoftware and provides with an efficient computational en-gine. Concerning the mechanical modeling, it is possibleto simulate linear or non-linear rigid or deformable bod-ies.

The numerical simulation strategies available inSiconos/Kernel are quasi-statics, smooth dynamics,nonsmooth dynamics, each one being either linearor non-linear and simulated with event–capturing orevent–detecting schemes. Available time integrationschemes are Moreau–Jean scheme, Schatzman–Paolischeme, nonsmooth Newmark scheme [9, 10], Odepacksuite and DAE solvers developed by E. Hairer [13].

Inside SICONOS/KERNEL, the description of the usermodel relies internally on a primary graph with dynam-ical systems as nodes and interactions as edges. Dur-ing time evolution, the determination of active constraintscorresponds to the building of sub-graphs of the primarygraph. In the case of problems formulated in local co-ordinates an adjoin graph transformation is dynamicallyapplied to sub graphs in order to drive the computationof the components of the optimization problem given toNumerics solver.

The primary graph structure may be entirely specifiedonce by the user, or it may also be rebuilt during the sim-ulation, as, for example, the result of a contact detectionbroad-phase. Links with pre/post processing softwarefor collision detection (Bullet contact detection [18]) andCAD libraries (OpenCascasde [29] and PythonOCC [25])has been set–up. The latter link enables the contact de-tection between bodies defined by B-Rep (splines, nurbs,...) and then to compute gaps and local frame at contact.Such a geometrical representation of the data allows touse realistic modeling of surfaces with large sliding. Thepossible impact laws for mechanics are complementarycondition, impact with or without friction.

SICONOS is written in C++ and has an object oriented ar-chitecture, there is no graphical user interface (GUI). Asimulation is run through a C++ or Python script in whichare gathered the objects creations and the method calls onthese object that make up the computation. Furthermore,not only the coarse level of command driving is avail-able, but the time loop can be exploded in every step toallow for an interactive simulation. In the same way thewhole database is accessible through copy or reference,allowing for a efficient access and aimed at designing anypost-processing functions.

More details can be found at http://siconos.gforge.inria.fr.

3.1. Rover simulation using Siconos Standalone

The Rover simulation in the Siconos platform allows usto simulate the robot motion taking into account rigor-ously dynamics and non-regular models of contact fric-tion. Roughly, coding a Siconos application consists intwo main steps : the first is to describe the dynamic Rovermodel and the contact model interaction between wheelsand the environment; the second is to define appropriatenumerical parameters for the model.

More precisly, any Siconos code (C++ or Python) is com-posed of the following sub-steps:

1. define some DynamicalSystem instances2. define some Interaction instances, and for each

Interaction:define Relationdefine NonSmoothLaw

3. build a NonSmoothDynamicalSystem : allDynamicalSystem + all Interaction objects ar-ranged into a directed Graph

4. build a Model that holds theNonSmoothDynamicalSystem.

5. define a Simulation: the way the behavior of theNonSmoothDynamicalSystem will be computed

define a TimeDiscretisationchoose a strategy: TimeStepping or

EventDrivendefine some integrators for the DynamicalSys-

tems (OneStepIntegrator)6. define a way to formalize and solve the possible

non smooth problems (formulation + solver, theOneStepNSProblem)

7. associate the Simulation to the Model8. launch the Simulation (time loop)

Modeling The Rover dynamical model is a La-grangianDS siconos object (lagrangian formulation). For3D Rover modeling, the inertia matrix and contact modelinteraction relations are difficult to set-up by hands. Weuse a MapleTMcode to automatically generate these re-lations, and to export into C files. In Siconos, we im-port these relations as a plug-in function that are dy-namically loaded. The HuMAns toolbox([31]) usingMapleTMsoftware tool enable us to easily do complexmodeling easily with high accuracy.

Originally developed for humanoid robotics research, theHuMAnS toolbox (for Humanoid Motion Analysis andSimulation) proposes a wealth of state - of - the - art al-gorithms from the field of robotics research for the mod-eling, the analysis and the simulation. In our case, weused it to generate the multi-body dynamic model for theRover. For this, the user need to describe the Rover pa-rameters through several MapleTMinput files. One filemust describe kinematic parameters of the Rover, it in-dicates the relative location of key-points of the modeland the degree of freedom of every connecting point. Another file describes the dynamical parameters, it describesthe inertials parameters: the gravity vector, the mass ofthe segment, the position of the segments centers of massand the inertia matrix of these segments relative to thecenters of their attached frames.

Page 5: MECHANICAL SIMULATION OF THE EXOMARS ROVER USING …robotics.estec.esa.int/ASTRA/Astra2013/Papers/Acary_2824437.pdf · body systems with contact and friction, all the previous software

SteeringAxleFR(q9)SteeringAxleFL(q8)

AxleF (q7)

WheelBR(q21)

AxleBR(q17)

WheelMR(q20)

SteeringAxleMR(q18)

WheelFR(q11)

SteeringML(q13)

AxleBL(q12)

SteeringAxleBL(q14)

WheelBL(q16)

WheelFL(q10)

WheelML(q15)

XY

Z

Mass CenterGlobal coordinates (q1, q2, q3)Orientation (q4, q5, q6)

SteeringAxleBR(q19)

Figure 1: Rover Siconos 3D representation and jointsnotation

Then, the MapleTMgenerator included in HuMAns pro-duces C code for M(q) the system inertia, G(q) theforces which derived from a potential energy (for exam-ple the gravity), N(q, q) a non-linear effects matrix.

For the simulation we used a simplified model inspiredfrom the ExoMars rover chassis with six wheels on threesimple passive bogies located forward at each side of therover and one on the rear (see [19]). The payload is sim-ply modelised with a mass uniform parallelepiped. Thevisual representation and joints notation are given on thefigure 1. The rover has 21 Degree Of Freeedom (DOF) :6 for the location of the rover, 6 for the rotation of eachwheel, 6 for each wheel steering and 3 for each passivejoint of the bogies.

To describe the contact of the Rover with the solid groundor granular soil in Siconos, we need two plugin functions:h to compute the distance between contact points and Gwhich is the transformation matrix of velocity of contactpoints from the global frame to the local frame.

To simplify the model, we only consider point contact. Inthis contact model, we simplify the axis of the wheel intoa point, and create contact model between this point andthe sphere, a plane or a mesh.

For the simulation results given below, the ground ismodeled by meshes. In order to be able to perform asimulation of the rover roaming on a triangular mesh inSiconos one needs to have the appropriate interaction andrelation classes defined. Relation class is an interface pro-viding distances between the surfaces being checked forcollision as well as jacobians, which in turn provide map-pings from the local to global coordinate frames. Whiledistances are needed for collision detection, jacobiansare crucial for resolving impacts and non-smooth frictionproblems. Distances calculation is a broad topic in itself,briefly speaking these can be delivered by a third-partycollision detection library or calculated according to anexplicit algorithm built-in in the respective relation class.In the standalone simulation the latter approach has beenchosen. Namely, distance function has been defined ex-plicitly in order to calculate the gap between the center ofeach wheel of the robot and a triangle arbitrarily orientedin space. Everytime this function returns zero (with cer-tain tolerance) a collision is declared. Jacobian is definedwithin the relation class as an operator resulting from the

multiplication of the local triangle’s rotation matrix withan inverse of robot’s geometric jacobian. Relation objecttogether with a non-smooth law define the interaction be-tween systems. In the standalone simulation an interac-tion is instantiated between each wheel and each triangle.Thus, there is six times as many interactions as wheels.This approach can become inefficient as the number oftriangles (and complexity of the mesh) grow. To com-pensate for this problem a space filter should be used inthe future which in essence filters out and discards inter-actions between objects which are far enough.

The C code generated, for the rover model and the contactmodel interaction, is then imported in Siconos code plu-gin function. It enables us to easily do complex modelingwith high accuracy. This work of modeling is detailed inthe report [16].

Simulation Results After the modeling step, wedescribe the simulation strategy and its parame-ters. For the simulations presented below, we in-stance a NewtonImpactNonSmootLlaw to simulatecontact, Moreau’s Time Stepping scheme and New-ton/AlartCurnier solver to solve the 3D friction prob-lem. Details on the simulation parametrizations can befound on [2]. On the Siconos platform, the 3-D visual-ization is done in a VRML environment. We simulate therover with differents initial condition and different envi-ronment.

In the sequel, several results are presented obtained fromthe standalone simulation of the rover in Siconos. Twocases are studied which corresponds to the main tests forthe design and analysis the chassis:

1. Obstacles overcoming: in our experiment, we testthe ability to go over an obstacle in the form of astep of 0.1 meter high

2. traction performance: in this latter experiment, wetest the ability of the rover to drive uphill withchanging wheels’ torques and a given coefficient offriction.

Obstacles overcoming In this test case, a 0.1 meterhigh step is set in front of the robot (Fig. 2). Severalimpacts occur when robot climbs the step. First impactis due to the fact that rover falls down onto the plane atthe beginning of the simulation. Following impacts affectnot only y velocity component but also x and z velocitycomponents and are due to the collision with the step.The restitution coefficient equals to 0.1 and the frictioncoefficient is equal to 0.35. Abrupt changes are observedin velocity of the robot’s centre of mass due to impacts.

Traction perfomance In this second test case the roveris moving up an inclined plane along the x axis of2.10−2 rad. The coefficient of friction coefficient is cho-sen sufficiently low to exhibit sliding under high torques.Six phases of motion have been distinguished in order todepict the various phenomena ans scenarios due to fric-tion:

Page 6: MECHANICAL SIMULATION OF THE EXOMARS ROVER USING …robotics.estec.esa.int/ASTRA/Astra2013/Papers/Acary_2824437.pdf · body systems with contact and friction, all the previous software

(a) Phase 1

(b) Phase 2

(c) Phase 3

Figure 2: Rover climbing the step

• no torque is applied to any of the wheels - time in-terval 0s ≤ t < t1 with t1 = 50s

• a constant torque counterbalancing the effect of thegravity is applied to all wheels - time interval t1 ≤t < t2 with t2 = 100s

• a linearly increasing torque is applied to all wheelsto stop the rover - time interval t2 ≤ t <t3 with t3 = 138.61s

• a constant torque counterbalancing the effect of thegravity is applied to all wheels - time interval t3 ≤t < t4 with t4 = 180s

• a linearly increasing torque is applied to all wheelsto stop the rover - time interval t4 ≤ t <t5 with t5 = 200s

• a high constant torque is applied to all wheels - timeinterval t5 ≤ t in order to produce sliding.

In Figure 3, one can see the evolution of rover’s mass cen-tre velocity. In the first phase ([t0, t1]), the rover is rollingwithout sliding under gravity load. In the second phasethe velocity is kept constant due to the driving torque thatcounteracts the gravity. In the third phase ([t2, t3]), thevelocity is decreasing in quadratic way with respect totime since the torque is linearly increasing. In the fourth([t3, t4]), the rover is stopped at rest in the slope. The fifthphase is similar to the third one. One can notice that in thelast phase of motion despite dramatic change in wheels’velocities rover’s trunk does not accelerate anymore. This

02000400060008000

10000

App

lied

torq

ue(N

.m) t1 t2 t3 t4 t5

-30

-25

-20

-15

-10

-5

0

5

10

15

q 1.

Trun

kx-

velo

city

(m/s

)0.50.60.70.80.9

11.11.2

50 100 150 200 250q 1Tr

unk

x-po

sitio

n(m

)

t (time s)

Figure 3: Motion of the rover in a slope under the actionof varying driving torques.

is due to the friction force saturation. Energy supplied tothe wheels is dissipated by friction and sliding.

One of the most important feature to note is that the idealCoulomb’s law is perfectly satisfied. In the case of aregularized model, some high frequency dynamics wouldhave been observed and the perfect zero relative velocityat contact is never obtained.

4. 3DROV

3DROV is a rover planetary exploration simulationframework developed by TRASYS. It uses as simula-tion framework the ESOC EGOS SimSat v4 tool8 andincludes both, models of the environment in which therover evolves (terrain, atmosphere, orbital and timekeep-ing) and models of the rover itself (mechanical, power,thermal, communications, payloads and a model of theo/b controller). 3DROV disposes also a 3D Visualizationcomponent that allows monitoring in a photo-realisticsynthetic environment the evolution of the simulation.Thanks to the use of the SMP (Simulation Model Porta-bility) the system provides the possibility to easily usemodels of different levels of fidelity depending on thescope of the simulation. 3DROV focuses on operationalsimulations for the validation of rover plans (composi-tion of rover Activities) spanning over one or several sols(experiment cycles). When planning rover operations in-cluding rover travelling, it is very important to be able

8http://www.egos.esa.int/portal/egos-web/products/Simulators/SIMSAT/

Page 7: MECHANICAL SIMULATION OF THE EXOMARS ROVER USING …robotics.estec.esa.int/ASTRA/Astra2013/Papers/Acary_2824437.pdf · body systems with contact and friction, all the previous software

to simulate this part of the plan as close as possible inorder to predict the Rover mechanical behaviour, to es-timate the path to be travelled and to evaluate the re-quired energy consumption. 3DROV uses the PhysX 9

physics engine and recently Bullet 10 for mechanical sim-ulation. Internal ESA work performed at ESTEC showedthat using PhysX the simulation results are qualitativelyconsistent with the expected behaviour but still insuffi-cient to support detailed rover motion validation. Theuse of SICONOS allows to involve better friction-contactmodel on a granular terrain and aims to improve the ex-isting 3DROV simulation framework providing accuratemechanical rover simulation. In addition, this work con-tributes to the openness of the system by establishing ageneric API for dynamics models/3D tools interaction.

Figure 4: 3DROV architecture

Siconos within 3DROV consists of several shared objectsgrouped inside the kernel and numerics shared libraries.It is integrated into the Rover Mechanical model compo-nent of 3DROV and interacts with a) the on-board con-troller model to receive the required trajectory and b) withthe 3D Visualisation tool to exchange collision informa-tion and the rover state. Figure 5 illustrates the Exomarsrover model into a test environment and on a planetaryterrain. The simulation ’step’ is triggered by the simula-tion framework scheduler.

Figure 5: ExoMars simulation in 3DROV

In particular, a dedicated API allows Siconos a) to re-trieve from the 3D Visualization component collision in-

9https://developer.nvidia.com/technologies/physx

10http://bulletphysics.org

formation including the number of contact points, coordi-nates of contact points, normal vector in the contact point,penetration as well as coefficients of friction and restitu-tion and b) to set the rover’s joints and the rover’s trunkposition and orientation.

5. CONCLUSION

3DROV is a rover planetary exploration simulationframework which allows different levels of fidelity de-pending on the scope of the simulation. PluggingSICONOS allows to involve better friction-contact mod-eling in view of robust and efficient simulations onground or with rigid obstacles and aims to improve theexisting 3DROV simulation framework providing accu-rate mechanical rover simulation.

We claim that handling this and that in the context ofnon-smooth dynamical systems provides, in particular inthe case of hard contacts, more representative results andsimplifies the modelling of the wheel/terrain interaction.

Next steps of this on-going work includes:

• benchmarking of SICONOS simulation results forstatic stability of the rover over steep slopes, slip-page handling and obstacles overcoming.

• comparison with results obtained using the usualphysical engines like Bullet, PhysX and ODE.

• simulation of more complex wheel/terrain interac-tion taking into account granular materials or theBekker model.

• continue the implementation of the3DROV/SICONOS API focussing on opennessand genericity both at model description level andinformation exchange during simulation.

REFERENCES

[1] V. Acary. Projected event-capturing time-steppingschemes for nonsmooth mechanical systems with unilat-eral contact and coulomb’s friction. Computer Methodsin Applied Mechanics and Engineering, 256:224 – 250,2013.

[2] V. Acary and B. Brogliato. Numerical methods for nons-mooth dynamical systems: applications in mechanics andelectronics, volume 35. Springer, 2008.

[3] V. Acary and F. Cadoux. Recent Advances in ContactMechanics, Stavroulakis, Georgios E. (Ed.), volume 56of Lecture Notes in Applied and Computational Mechan-ics, chapter Applications of an existence result for theCoulomb friction problem. Springer Verlag, 2013.

[4] V. Acary, F. Cadoux, C. Lemarechal, and J. Malick. Aformulation of the linear discrete Coulomb friction prob-lem via convex optimization. ZAMM - Journal of AppliedMathematics and Mechanics / Zeitschrift fur AngewandteMathematik und Mechanik, 91(2):155–175, 2011.

[5] AESCO. Matlab/Simulink module AESCO soft soil tyremodel (AS2TM) users guide, 2003.

Page 8: MECHANICAL SIMULATION OF THE EXOMARS ROVER USING …robotics.estec.esa.int/ASTRA/Astra2013/Papers/Acary_2824437.pdf · body systems with contact and friction, all the previous software

[6] M. G. Bekker. Introduction to terrain vehicle systems.University of Michigan Press, Ann Arbor, USA, 1969.

[7] M. G. Bekker. The development of a moon rover. Journalof the British Interplanetary Society, 38(537–543), 1985.

[8] J. Cameron, A. Jain, t. Huntsberger, G. Sohl, andR. Mukherjee. Vehicle-terrain interaction modeling andvalidation for planetary rovers. Technical Report 10-15, National Aeronautics and Space Administration. JetPropulsion Laboratory. California Institue of Technology,Pasadena, California, 2009.

[9] Q. Z. Chen, V. Acary, G. Virlez, and O. Bruls. ANewmark-Type Integrator for Flexible Systems Consid-ering Nonsmooth Unilateral Constraints. In Peter Eber-hard, editor, The Second Joint International Conferenceon Multibody System Dynamics - IMSD 2012, Stuttgart,Germany, March 2012.

[10] Q.-Z. Chen, V. Acary, G. Virlez, and O. Bruls. A nons-mooth generalized-α scheme for flexible multibody sys-tems with unilateral constraints. International Journal forNumerical Methods in Engineering, 2012. submitted.

[11] Andreas Gibbesch and Bernd Schafer. Multibody systemmodelling and simulation of planetary rover mobility onsoft terrain. In Proc. of 8th Int. Symp. on Artificial In-telligence, Robotics and Automation in Space, i-SAIRAS,2005.

[12] M. Haddouni, V. Acary, and J.D. Beley. Comparison ofindex-3, index-2 and index-1 dae solvers for nonsmoothmultibody systems with unilateral or bilateral constraints.In Eccomas. MultiBody dynamics 2013., July 2013.

[13] E. Hairer, S.P. Norsett, and G. Wanner. Solving OrdinaryDifferential Equations I. Nonstiff Problems. Springer,1993.

[14] A. Jain, J. Balaram, J. Cameron, J. Guineau, C. Lim,M. Pomerantz, and G. Sohl. Recent developments inthe roams planetary rover simulation environment. InAerospace Conference, 2004. Proceedings. 2004 IEEE,volume 2, pages 861–876 Vol.2, 2004.

[15] A. Jain, J. Guineau, C. Lim, W. Lincoln, M. Pomer-antz, G. Sohl, and R. Steele. Roams: Planetary surfacerover simulation environment. In in International Sympo-sium on Artificial Intelligence, Robotics and Automationin Space (i-SAIRAS 2003, 2003.

[16] supervisor: Vincent Acary Jianhui Yang. Simulation ofa mars rover on granular soils. Technical report, INRIA,Erasmus Mundus Master Internship, 2010.

[17] C Lee, J Dalcolmo, S Klinkner, L Richter, G Terrien,A Krebs, R Siegwart, L Waugh, and C Draper. Designand manufacture of a full size breadboard exomars roverchassis. In Proceedings of 9th ESA workshop on advancedspace technologies for robotics and automation, Noord-wijk, the Netherlands: Astrionic Press, pages 28–39. Cite-seer, 2006.

[18] Bullet Physics Library. http://bulletphysics.org.

[19] S Michaud, A Gibbesch, T Thueer, A Krebs, C Lee, B De-spont, B Schafer, and R Slade. Development of the ex-omars chassis and locomotion subsystem. In 9th Inter-national Symposium on Artificial Intelligence. UniversalCity, CA,, USA: Robotics and Automation for Space (i-SAIRAS 2008), 2008.

[20] S Michaud, M Hoepflinger, T Thueer, C Lee, A Krebs,B Despont, A Gibbesch, and L Richter. Lesson learnedfrom exomars locomotion system test campaign. In Pro-ceedings of 10th Workshop on Advanced Space Technolo-gies for Robotics and Automation, ESTEC The Nether-lands, 2008.

[21] N. Patel, A. Ellery, E. Allouis, M. Sweeting, andL. Richter. Rover mobility performance evaluation tool(rmpet): A systematic tool for rover chassis evaluation viaapplication of bekker theory. In 8th ESA Workshop onAdvanced Space Technologies for Robotics and Automa-tion, ASTRA 2004, pages 251–258. ESTEC, Noordwijk,The Netherlands, 2-4 November 2004.

[22] Nildeep Patel, Richard Slade, and Jim Clemmet. The ex-omars rover locomotion subsystem. Journal of Terrame-chanics, 47(4):227–242, 2010.

[23] P. Poulakis, L Joudrier, and S Stramigioli. Port-basedmodeling and simulation of planetary rover locomotion onrough terrain. In 9th ESA Workshop on Advanced SpaceTechnologies for Robotics and Automation (ASTRA’06),Noordwijk, The Netherlands. Citeseer, 2006.

[24] P. Poulakis, L. Joudrier, S. Wailliez, and K.Kapellos.3drov: A planetary rover system design, simulation andverification tool. In 10th International Symposium on Ar-tificial Intelligence, Robotics and Automation in Space, i-SAIRAS-08, Hollywood,USA, February 26-29 2008.

[25] PythonOCC. 3D CAD/CAE/PLM development frame-work for the Python programming language. http://www.pythonocc.org.

[26] F. Radjaı and F. Dubois, editors. Discrete–element model-ing of granular materials. Iste. John Wiley & Sons, 2011.

[27] R.T. Rockafellar. Convex Analysis. Princeton UniversityPress, 1970.

[28] T. Oechslin S. Michaud, P. Oettershagen. Wheel leveltest data generation and utilization to predict locomotionperformances of planetary rovers and validate simulationtools. In Proceedings of International Symposium on Ar-tificial Intelligence, Robotics and Automation in Space, i-SAIRAS, 2012.

[29] Open CASCADE Technology. http://www.opencascade.org.

[30] Martin Wassink, Raffaella Carloni, Pantelis Poulakis, andStefano Stramigioli. Digital elevation map reconstructionfor port-based dynamic simulation of contacts on irreg-ular surfaces. In Intelligent Robots and Systems, 2009.IROS 2009. IEEE/RSJ International Conference on, pages5179–5184. IEEE, 2009.

[31] P.-B. Wieber, F. Billet, R. Boissieux, L.and Pissard-Gibollet, et al. The humans toolbox, a homogenous frame-work for motion capture, analysis and simulation. In Inter-national Symposium on the 3D Analysis of Human Move-ment, 2006.

[32] J. Yen, A. Jain, and J. Balaram. Roams: Rover analysis,modeling and simulation. In In Proceedings of the 1999International Symposium on Art Intelligence, Roboticsand Automation for Space, pages 249–254, 1999.