Module: MJSystemMassMatrix

Executive Summary

The MJSystemMassMatrix module extracts the full system mass matrix. It also stores the number of spacecraft in the scene, indexes their starting joint, and the types of joints used.

Note

This module assumes that each body in the MuJoCo scene that is a direct child of the world body is a separate spacecraft so long as it has at least one joint. If a free joint is used as part of a spacecraft, it must be used as the first joint of that spacecraft.

Message Connection Descriptions

The following table lists all the module input and output messages. The module msg connection is set by the user from python. The msg type contains a link to the message structure definition, while the description provides information on what this message is used for.

Module I/O Messages

Msg Variable Name

Msg Type

Description

massMatrixOutMsg

MJSysMassMatrixMsgPayload

system mass matrix C ++ output msg in generalized coordinates

User Guide

This section is to outline the steps needed to setup the MJSystemMassMatrix module in Python using Basilisk.

  1. Import the MJSystemMassMatrix class:

    from Basilisk.simulation import MJSystemMassMatrix
    
  2. Enable extra EOM call when building the Mujoco scene:

    scene.extraEoMCall = True
    
  3. Create an instance of MJSystemMassMatrix:

    module = MJSystemMassMatrix.MJSystemMassMatrix()
    
  4. Set the scene the module is attached to:

    module.scene = scene
    
  5. The MJSystemMassMatrix output message is massMatrixOutMsg.

  6. Add the module to the task list:

    unitTestSim.AddModelToTask(unitTaskName, module)
    

class MJSystemMassMatrix : public SysModel
#include <MJSystemMassMatrix.h>

This is a C++ module to extract the system mass matrix from Mujoco.

Public Functions

MJSystemMassMatrix() = default
~MJSystemMassMatrix() = default

This is the constructor for the module class.

void Reset(uint64_t CurrentSimNanos)

This is the destructor for the module class.

void UpdateState(uint64_t CurrentSimNanos)

This method is used to reset the module and checks that the scene is setup.

Public Members

MJScene *scene = {nullptr}

pointer to the MuJoCo scene

This method is used to extract the total spacecraft mass matrix from the MuJoCo scene.

Message<MJSysMassMatrixMsgPayload> massMatrixOutMsg

system mass matrix C++ output msg in generalized coordinates

BSKLogger bskLogger

BSK Logging.

Private Members

std::size_t nDOF = {0}

number of total DOF

std::size_t nSC = {0}

number of spacecraft in the system

std::vector<std::size_t> scStartIdx

list of the first joint index for each spacecraft

std::vector<std::size_t> jointTypes

list of joint types in the system