-
Notifications
You must be signed in to change notification settings - Fork 1
Gathering Scenario Data for Import
This topic continues the tutorial on building a package for the simple pendulum by describing the data generation, data export, and data import. It will rely on the file system basis developed in the previous tutorials addressing the Developing the Controller and Developing the Analyzer. This topic will cover generating model scenario data from a standalone application, exporting that data into a Reveal compatible format, and then importing the data into the Reveal database. In most instances model scenario data will need to be transferred to the database host and imported manually using the provided import utility.
Data can be generated from a number of sources. Reveal provides an Export and Import framework to enable data to be gathered from any source and then ported into the Reveal database. If the Reveal database resides on the system where data is being gathered, then the data can be directly inserted into the database using the Reveal data structures; however, this is only an option for systems with a full installation. The Reveal Exporter and Importer use a combination of xml and flat files to maximize flexibility while minimizing complexity and file size. Details of the xml schema are beyond the scope of this tutorial, but after running the data generator, the xml schema can be easily discerned and applied to a variety of data source.
The exporter and importer rely on a combination of four files to define the data for a scenario. The data of interest for importing are the scenario definition, the analyzer definition, the trial data, and the model solution data. These files must have the extensions .scenario
, .analyzer
, .trials
, and .solutions
respectively. If these files are automatically produced by the exporter, they will have a unique identifier for the stem file name. The unique identifier is used rather than the package name as it is possible to have multiple scenarios use the same package. The scenario file is an xml based file that contains the definitions and references to the other files. When running the importer and as long as all four files are available, the only file that needs to be provided to the importer is the scenario file. The analyzer file is also an xml file and can be loaded through the importer without an accompanying scenario file, but it is not the recommended approach at this time. The trials and solutions files are flat space separated files whose column structures are defined in the scenario file.
The following example demonstrates generating data for the pendulum package previously discussed using a principled approach and the provided exporter. For the alternate direct insert approach refer to the implementation in the repository.
The data generator uses Ordinary Differential Equations (ODEs) to model the motion of a pendulum when acted on by only the force of gravity. Integration of the ODEs is executed by the boost numerics odeint
library so it is required for this tutorial. The example in the repository supports usage of either the Runge-Kutta or Euler integrators; however, the following example will only present usage of the Runge-Kutta integrator.
There has been a relatively recent increment of odeint
versioning which regretably resulted in a significant change in the odeint
interfaces. The example in the repository supports both interfaces, but the following example will demonstrate only the version 2 interface.
In the pendulum scenario directory stored in the repository, there is an additional directory named data
not covered in the previous tutorials. This directory contains the data generator and the build script necessary to generate data. Additionally, refer to the repository version of the parent scenario directory CMakeLists.txt for additional requirements to successfully build and run the generator.
The ODEs and the integrator are defined in the pendulum.h
file in the data
directory. These definitions are used by odeint
to compute the changing state of the pendulum over a number of integrations.
#include <vector>
#include <boost/numeric/odeint.hpp>
#include <boost/shared_ptr.hpp>
//----------------------------------------------------------------------------
// Type definitons
class pendulum_c;
typedef boost::shared_ptr<pendulum_c> pendulum_ptr;
typedef std::vector< double > state_t;
typedef boost::numeric::odeint::controlled_runge_kutta< boost::numeric::odeint::runge_kutta_cash_karp54< state_t > > stepper_t;
//----------------------------------------------------------------------------
class pendulum_c {
private:
double _l; //< the length of the pendulum arm
public:
double q; //< to store the joint angle of the pivot joint
double dq; //< to store the joint velocity of the pivot joint
/// Parameterized constructor
/// @param l the length of the pendulum arm
/// @param q_0 the initial joint angle of the pivot joint
/// @param dq_0 the initial joint velocity of the pivot joint
pendulum_c( double l, double q_0, double dq_0 ) {
_l = l;
q = q_0;
dq = dq_0;
}
/// The pendulum ode computation. Interface for odeint integrators
/// @param[in] x_0 the state before integration where x_0[0] is position and
/// x_0[1] is velocity
/// @param[out] x_1 the state after integration where x_1[0] is position and
/// x_1[1] is velocity
/// @param[in] t the virtual time of the integration step
void operator()( const state_t& x_0, state_t& x_1, const double t ) {
x_1[0] = x_0[1];
x_1[1] = -9.8 / _l * sin( x_0[0] );
}
};
The generator.cpp
file contains the actual simulator implementation for data generation. The generator starts the pendulum rotated ninety degrees from equilibrium at rest with a start time of 0 seconds. It then integrates the pendulum forward 10 seconds using a time step of 0.001 seconds. Before each step, the simulator copies the current state of the pendulum into a trial and after each step it copies the current state into a solution. It then writes the trial and solution to disk using the exporter. However, before integration starts there are a number of preparation steps that occur to set up the simulator and the exporter. The steps required for the simulator will be considered self explanatory through comments, but the exporter setup will be explained briefly and the complete code will be listed after for full reference.
To initialize the exporter, a scenario definition, an analyzer definition, a trial prototype, and a solution prototype must be created. The scenario and analyzer definitions are provided through the define_scenario(...)
and define_analyzer(...)
helper functions and are called during initialization. The prototype solution is generated as the initial_state
variable in the main function along with a trial instance. These four files are then passing into the exporter through the write(scenario, analyzer, solution, trial)
interface which allows the exporter to build the files which requires mapping the fields from the prototype trial and solution to the columns in their respective flat output files. No data is actually written to the flat files yet, but the scenario and analyzer definitions will be written.
Once the exporter has been mapped the fields and readied the files for export, each trial or solution record is written to file when the exporter write( trial )
or write( solution )
function is called. The first call to write and before integration initial_state
must be provided. Once the integration has started, the trial and solution obejcts are written in sequence.
#include "pendulum.h"
#include <stdio.h>
#include <reveal/core/pointers.h>
#include <reveal/core/system.h>
#include <reveal/core/model.h>
#include <reveal/core/scenario.h>
#include <reveal/core/analyzer.h>
#include <reveal/core/trial.h>
#include <reveal/core/solution.h>
#include <reveal/core/exporter.h>
//----------------------------------------------------------------------------
// Constants
#define PI 3.14159265359
//----------------------------------------------------------------------------
// Scenario Defintion Values
double _sample_rate = 0.001;
double _start_time = 0.0;
double _end_time = 10.0;
//----------------------------------------------------------------------------
// Initial state
#define PENDULUM_LENGTH 1.0
#define INITIAL_q PI / 2.0
#define INITIAL_dq 0.0
//----------------------------------------------------------------------------
// Variables
pendulum_ptr _pendulum; //< the pendulum ODEs
Reveal::Core::scenario_ptr _scenario; //< scenario definition
Reveal::Core::analyzer_ptr _analyzer; //< analyzer definition
/// exporter writes all scenario data to a compatible Reveal import format
Reveal::Core::exporter_c _exporter;
/// Accurate time spec to correct error from inaccurate floating point addition
long _sec; //< seconds portion of current time
long _nsec; //< nanoseconds portion of current time
//----------------------------------------------------------------------------
/// Reads the currently stored time and returns as a floating point value
/// @return the current time in a double format
double get_time( void ) {
return (double)_sec + ((double)_nsec / (double)1E9);
}
//----------------------------------------------------------------------------
/// Converts the floating point time step into a more accurate representation,
/// updates the stored time based on the time step, returns the current time
/// @param dt the time step to add to the currently stored time
double update_time( double dt ) {
// split the time differentials into whole seconds and whole nanoseconds
double dt_sec = floor( dt );
double dt_nsec = dt - dt_sec;
// convert the floating point time differentials to long differentials
long nsec_step = (long) (dt_nsec * 1E9);
long sec_step = (long) dt_sec;
// increment the stored time using the long differentials
_nsec += nsec_step;
_sec += sec_step;
// if nanoseconds has accrued a second through increment, correct the values
if( _nsec > 1E9 ) {
_nsec -= 1E9;
_sec += 1;
}
// get the newly updated time and return it as a floating point value
return get_time();
}
//----------------------------------------------------------------------------
/// Creates a fixed base link reference
/// @return a Reveal link defining the fixed base link state in the world frame
Reveal::Core::link_ptr base_link( void ) {
// base is positoned at 0,0,0 and rotated 90 degrees to compensate for model
// definition in sdf. The link is fixed to the world and cannot move.
// create the link object
Reveal::Core::link_ptr base( new Reveal::Core::link_c( "base_link" ) );
// set the link state relative to the world frame
base->state.linear_x( 0.0 );
base->state.linear_y( 0.0 );
base->state.linear_z( 0.0 );
base->state.angular_x( PI / 4 );
base->state.angular_y( 0.0 );
base->state.angular_z( 0.0 );
base->state.angular_w( PI / 4 );
base->state.linear_dx( 0.0 );
base->state.linear_dy( 0.0 );
base->state.linear_dz( 0.0 );
base->state.angular_dx( 0.0 );
base->state.angular_dy( 0.0 );
base->state.angular_dz( 0.0 );
// return the link object
return base;
}
//----------------------------------------------------------------------------
/// Creates a joint for the pivot
/// @return a Reveal joint defining the current state of the pivot joint
Reveal::Core::joint_ptr pivot_joint( void ) {
// pivot rotates based on the current ode computation. reads the ode state
// and writes that state into a reveal joint
// create the joint object
Reveal::Core::joint_ptr pivot( new Reveal::Core::joint_c( "pivot_joint" ) );
// define the number of state and controls needed for this joint
pivot->state.resize( 1 ); // joint has 1 DOF
pivot->control.resize( 0 ); // joint uses no controls
// Note: the model is rotated 90 degrees in the scenario world frame from
// its model frame so the state is adjusted accordingly
pivot->state.q( 0, _pendulum->q - PI/2.0 ); // set position
pivot->state.dq( 0, _pendulum->dq ); // set velocity
// return the joint object
return pivot;
}
//----------------------------------------------------------------------------
/// Creates a scenario definition
/// @return the scenario definition for the pendulum scenario
Reveal::Core::scenario_ptr define_scenario( void ) {
// create the scenario object
Reveal::Core::scenario_ptr scenario( new Reveal::Core::scenario_c() );
// set the scenario parameters
scenario->id = generate_uuid();
scenario->package_id = "pendulum";
scenario->description = "a pendulum acting under gravity alone";
scenario->sample_rate = _sample_rate;
scenario->sample_start_time = _start_time;
scenario->sample_end_time = _end_time;
// return the scenario object
return scenario;
}
//----------------------------------------------------------------------------
/// Creates an analyzer definition
/// @return the analyzer definition for the pendulum scenario
Reveal::Core::analyzer_ptr define_analyzer( Reveal::Core::scenario_ptr scenario ) {
// create the analyzer object
Reveal::Core::analyzer_ptr analyzer( new Reveal::Core::analyzer_c() );
// set the analyzer parameters
analyzer->scenario_id = scenario->id;
analyzer->source_path = "pendulum/analyzers/pivot_angle";
analyzer->build_path = "pendulum/analyzers/pivot_angle/build";
analyzer->build_target = "libanalyzer.so";
analyzer->type = Reveal::Core::analyzer_c::PLUGIN;
// define the keys and user friendly labels for the analysis
analyzer->keys.push_back( "t" );
analyzer->labels.push_back( "Virtual time (s)" );
analyzer->keys.push_back( "delta" );
analyzer->labels.push_back( "Joint angle error" );
// return the analyzer object
return analyzer;
}
//----------------------------------------------------------------------------
/// Creates a trial definition
/// @param scenario the scenario definition who will own this trial
/// @param t the time of the trial
/// @return the trial definition generated for the current time
Reveal::Core::trial_ptr define_trial( Reveal::Core::scenario_ptr scenario, double t ) {
// create the trial object
Reveal::Core::trial_ptr trial( new Reveal::Core::trial_c() );
// set the trial parameters
trial->scenario_id = scenario->id;
trial->t = t;
// define all the models for this trial
Reveal::Core::model_ptr model( new Reveal::Core::model_c( "pendulum" ) );
model->insert( base_link() );
model->insert( pivot_joint() );
trial->models.push_back( model );
// return the trial object
return trial;
}
//----------------------------------------------------------------------------
/// Creates a model solution definition
/// @param scenario the scenario definition who will own this solution
/// @param t the time of the solution
/// @return the model solution definition generated for the current time
Reveal::Core::solution_ptr define_solution( Reveal::Core::scenario_ptr scenario, double t ) {
// create the model solution object
Reveal::Core::solution_ptr solution( new Reveal::Core::solution_c( Reveal::Core::solution_c::MODEL ) );
// set the solution parameters
solution->scenario_id = scenario->id;
solution->t = t;
// define all the models for this solution
Reveal::Core::model_ptr model( new Reveal::Core::model_c( "pendulum" ) );
model->insert( base_link() );
model->insert( pivot_joint() );
solution->models.push_back( model );
// return the solution object
return solution;
}
//----------------------------------------------------------------------------
/// Initializes all objects necessary to generate data
/// @return returns true if data generation is ready to proceed OR false if
/// the operation fails for any reason
bool init( void ) {
// create the pendulum
double l = PENDULUM_LENGTH;
double q_0 = INITIAL_q;
double dq_0 = INITIAL_dq;
_pendulum = pendulum_ptr( new pendulum_c( l, q_0, dq_0 ) );
// intialize time which internally maintained as longs for accuracy
_sec = 0;
_nsec = 0;
// get the scenario and analyzer definitions
_scenario = define_scenario();
_analyzer = define_analyzer( _scenario );
return true;
}
//----------------------------------------------------------------------------
/// Clean up all components that require a clean exit
void shutdown( void ) {
}
//----------------------------------------------------------------------------
/// Integrates the pendulum forward and updates subsequent state
/// @param[in] dt the integration step size
/// @param[in] t0 the time preceding integration
/// @param[out] t1 the time after integration has completed
void step( double dt, double t0, double& t1 ) {
state_t x( 2 ); // odeint compatible state vector
// update the state vector with current state
x[0] = _pendulum->q;
x[1] = _pendulum->dq;
// compute the end time t1
t1 = t0 + dt;
// integrate
boost::numeric::odeint::integrate_adaptive( stepper_t(), *_pendulum.get(), x, t0, t1, dt );
// update the pendulum state data structure from the odeint computed state
_pendulum->q = x[0];
_pendulum->dq = x[1];
}
//----------------------------------------------------------------------------
/// The generator application produces a set of Reveal import compatible files
/// defining the pendulum scenario for a pendulum acting under gravity with no
/// control inputs. The pendulum is started at an angle orthogonal to the
/// equilibrium axis and oscillates back and forth for a number of seconds.
int main( void ) {
double t, tf, dt; // time variables
Reveal::Core::trial_ptr trial; // the current trial definition
Reveal::Core::solution_ptr solution; // the current solution definition
// initialize all components that support the generator
if( !init() ) {
printf( "ERROR: Initialization failed.\nExiting\n" );
shutdown();
return 1;
}
// initialize local time variables
t = _start_time;
dt = _sample_rate;
// compute initial state; also acts as a solution prototype
Reveal::Core::solution_ptr initial_state = define_solution( _scenario, t );
// get a prototype for the trial; solution prototype is initial_state
trial = define_trial( _scenario, t );
// export the scenario framework.
// Note: the trial and initial_state content is not actually written, but
// the structure of all models contained in them is used to map fields to
// joint and link ids when actual data is available
bool result = _exporter.write( _scenario, _analyzer, initial_state, trial );
if( !result ) {
printf( "ERROR: Failed to write export framework.\nExiting\n" );
shutdown();
return 2;
}
// write initial state
_exporter.write( initial_state );
// simulate until the end time is reached
while( t <= _end_time ) {
// define the trial for the current time
trial = define_trial( _scenario, t );
// integrate the pendulum state forward an amount of time dt beginning at
// time t. tf is computed (and not necessary to this implementation)
step( dt, t, tf );
// update time using a more accurate time method rather than relying on tf
t = update_time( dt );
// define the solution for time t (now corresponds to time tf)
solution = define_solution( _scenario, t );
// write the trial and solution
_exporter.write( trial );
_exporter.write( solution );
// output the state for debugging
std::cout << t << " " << _pendulum->q << " " << _pendulum->dq << std::endl;
}
// report success and exit cleanly
printf( "Data generation succeeded\n" );
shutdown();
return 0;
}
//-----------------------------------------------------------------------------
If the example provided in the repository is followed, the data generator will be built along side the other scenario libraries in the root of the build
directory. To execute this data generator, navigate to the build directory and execute the following command:
./data-generator
The generator will print state to the console each iteration and will produce the four data files in the same directory if it was successful. If it failed, it should report an ERROR
to the console.
Before importing data into the database, please refer to the Review configuration documentation and in particular to Environmental Configuration and Populating the Database
Import can only be run on the Reveal database host machine with the backend database service running. The environment must also be set up properly for the importer to communicate with the appropriate database. Therefore, source the setup.sh
file before executing the import.
As mentioned above, the file stem was a randomly generated unique identifier, so this tutorial cannot explicitly describe the file names. Instead, a comparable example will be used.
After running the data-generator the scenario build directory contained the following files:
525e3080-c023-437b-a816-eb21cefa9b2e.analyzer data
525e3080-c023-437b-a816-eb21cefa9b2e.scenario data-generator
525e3080-c023-437b-a816-eb21cefa9b2e.solutions gazebo
525e3080-c023-437b-a816-eb21cefa9b2e.trials libgz-plugin.so
CMakeCache.txt Makefile
CMakeFiles models
cmake_install.cmake
To import the data after following the necessary configuration steps, run the following command:
reveal_db_import <path-to-build-directory> 525e3080-c023-437b-a816-eb21cefa9b2e.scenario
The importer will report the number of trials and solutions imported into the database.