mc_observers::BodySensorObserver Struct Reference

#include <mc_observers/BodySensorObserver.h>

Inheritance diagram for mc_observers::BodySensorObserver:
Collaboration diagram for mc_observers::BodySensorObserver:

Public Member Functions

 BodySensorObserver (const std::string &type, double dt)
 
void configure (const mc_control::MCController &ctl, const mc_rtc::Configuration &) override
 
void reset (const mc_control::MCController &ctl) override
 Resets the observer. More...
 
bool run (const mc_control::MCController &ctl) override
 Determines the pose of the floating base. More...
 
void update (mc_control::MCController &ctl) override
 Update the robot's floating base from its estimated pose. More...
 
const sva::PTransformd & posW () const
 Get floating-base pose in the world frame. More...
 
const sva::MotionVecd & velW () const
 Get floating-base velocity in the world frame. More...
 
- Public Member Functions inherited from mc_observers::Observer
 Observer (const std::string &type, double dt)
 
virtual ~Observer ()=default
 
void name (const std::string &name)
 Set the observer's name. More...
 
const std::string & name () const noexcept
 Returns the observer's name. More...
 
void addToLogger_ (const mc_control::MCController &ctl, mc_rtc::Logger &logger, const std::string &category="")
 Add observer entries to the logger under the categrory "category + name()". More...
 
void removeFromLogger_ (mc_rtc::Logger &logger, const std::string &category="")
 Remove observer from logger. More...
 
void addToGUI_ (const mc_control::MCController &ctl, mc_rtc::gui::StateBuilder &gui, std::vector< std::string > category={})
 Add observer to the gui under category {category, name()}. More...
 
void removeFromGUI_ (mc_rtc::gui::StateBuilder &gui, std::vector< std::string > category={})
 Remove observer from gui. More...
 
const std::string & desc () const noexcept
 Short description of the observer. More...
 
const std::string type () const noexcept
 
const std::string & error () const noexcept
 
double dt () const noexcept
 

Protected Types

enum  Update { Update::Control, Update::Sensor }
 

Protected Member Functions

void addToLogger (const mc_control::MCController &, mc_rtc::Logger &, const std::string &category) override
 Add observer from logger. More...
 
void addToGUI (const mc_control::MCController &, mc_rtc::gui::StateBuilder &, const std::vector< std::string > &category) override
 Add observer information the GUI. More...
 
- Protected Member Functions inherited from mc_observers::Observer
virtual void removeFromLogger (mc_rtc::Logger &, const std::string &)
 Remove observer from logger. More...
 
virtual void removeFromGUI (mc_rtc::gui::StateBuilder &, const std::vector< std::string > &category)
 Remove observer from GUI. More...
 

Protected Attributes

Update updateFrom_ = Update::Sensor
 
std::string fbSensorName_
 
sva::PTransformd posW_ = sva::PTransformd::Identity()
 
sva::MotionVecd velW_ = sva::MotionVecd::Zero()
 
sva::MotionVecd accW_ = sva::MotionVecd::Zero()
 
std::string robot_
 
std::string updateRobot_
 
bool updatePose_ = true
 
bool updateVel_ = true
 
bool logPos_ = true
 
bool logVel_ = true
 
bool logAcc_ = true
 
bool guiPos_ = false
 
bool guiVel_ = true
 
mc_rtc::gui::ArrowConfig guiVelConfig_
 
bool guiAcc_ = false
 
mc_rtc::gui::ArrowConfig guiAccConfig_
 
bool advancedGUI_ = false
 When true, displays an Advanced tab in the GUI. More...
 
- Protected Attributes inherited from mc_observers::Observer
std::string name_
 Observer name. More...
 
std::string type_
 Observer type. More...
 
std::string desc_
 Short description of the observer and its configuration. More...
 
std::string error_
 Descriptive error message to show if the observer failed. More...
 
double dt_
 Timestep. More...
 

Detailed Description

The BodySensorObserver is responsible for estimating the state of a robot's floating base from sensor measurements provided by a BodySensor and the kinematics beween this sensor and the floating base. It is assumed here that the floating base sensor kinematics estimate are synchronized.

See also
BodySensorObserver::run() for usage requirements

The default configuration estimates the floating base pose from the main bodysensor (typically an IMU).

Member Enumeration Documentation

◆ Update

Enumerator
Control 

Use the control robot floating base state.

Sensor 

Use the body sensor to determine the floating base pose.

Constructor & Destructor Documentation

◆ BodySensorObserver()

mc_observers::BodySensorObserver::BodySensorObserver ( const std::string &  type,
double  dt 
)
inline

Member Function Documentation

◆ addToGUI()

void mc_observers::BodySensorObserver::addToGUI ( const mc_control::MCController ,
mc_rtc::gui::StateBuilder ,
const std::vector< std::string > &   
)
overrideprotectedvirtual

Add observer information the GUI.

Default implementation does nothing, each observer implementation is responsible for adding its own elements to the GUI.

Parameters
categoryCategory in which to add this observer

Reimplemented from mc_observers::Observer.

◆ addToLogger()

void mc_observers::BodySensorObserver::addToLogger ( const mc_control::MCController ,
mc_rtc::Logger ,
const std::string &   
)
overrideprotectedvirtual

Add observer from logger.

Default implementation does nothing, each observer implementation is responsible for adding its own log entries

Parameters
categoryCategory in which to log this observer

Reimplemented from mc_observers::Observer.

◆ configure()

void mc_observers::BodySensorObserver::configure ( const mc_control::MCController ctl,
const mc_rtc::Configuration  
)
overridevirtual

Configure observer

Reimplemented from mc_observers::Observer.

◆ posW()

const sva::PTransformd& mc_observers::BodySensorObserver::posW ( ) const
inline

Get floating-base pose in the world frame.

◆ reset()

void mc_observers::BodySensorObserver::reset ( const mc_control::MCController ctl)
overridevirtual

Resets the observer.

Default implementation ensures that the BodySensor provided in the configuration exists and compute the initial floating base pose (calls run())

Parameters
ctlThe controller running this observer

Implements mc_observers::Observer.

◆ run()

bool mc_observers::BodySensorObserver::run ( const mc_control::MCController ctl)
overridevirtual

Determines the pose of the floating base.

The pose of the floating base is determined depending on the update type chosen:

  • Update::Control: copies the floating base position from the control robot (no estimation)
  • Update::Sensor: Computes the position of the floating base from a BodySensor and the kinematic chain between it and the floating base. If the BodySensor is not directly attached to the floating base link, this estimator requires accurate estimation of the robot kinematics. A typical pipeline will achieve this by running the EncoderObserver observer before the BodySensorObserver.

    It is assumed here that the floating base sensor and encoders are synchronized.

Parameters
ctlThe controller instance running this observer

Implements mc_observers::Observer.

◆ update()

void mc_observers::BodySensorObserver::update ( mc_control::MCController ctl)
overridevirtual

Update the robot's floating base from its estimated pose.

See also
run for usage requirements
Note
Calls rbd::forwardKinematics and rbd::forwardVelocity

Implements mc_observers::Observer.

◆ velW()

const sva::MotionVecd& mc_observers::BodySensorObserver::velW ( ) const
inline

Get floating-base velocity in the world frame.

Member Data Documentation

◆ accW_

sva::MotionVecd mc_observers::BodySensorObserver::accW_ = sva::MotionVecd::Zero()
protected

◆ advancedGUI_

bool mc_observers::BodySensorObserver::advancedGUI_ = false
protected

When true, displays an Advanced tab in the GUI.

◆ fbSensorName_

std::string mc_observers::BodySensorObserver::fbSensorName_
protected

◆ guiAcc_

bool mc_observers::BodySensorObserver::guiAcc_ = false
protected

◆ guiAccConfig_

mc_rtc::gui::ArrowConfig mc_observers::BodySensorObserver::guiAccConfig_
protected

◆ guiPos_

bool mc_observers::BodySensorObserver::guiPos_ = false
protected

◆ guiVel_

bool mc_observers::BodySensorObserver::guiVel_ = true
protected

◆ guiVelConfig_

mc_rtc::gui::ArrowConfig mc_observers::BodySensorObserver::guiVelConfig_
protected

◆ logAcc_

bool mc_observers::BodySensorObserver::logAcc_ = true
protected

◆ logPos_

bool mc_observers::BodySensorObserver::logPos_ = true
protected

◆ logVel_

bool mc_observers::BodySensorObserver::logVel_ = true
protected

◆ posW_

sva::PTransformd mc_observers::BodySensorObserver::posW_ = sva::PTransformd::Identity()
protected

◆ robot_

std::string mc_observers::BodySensorObserver::robot_
protected

◆ updateFrom_

Update mc_observers::BodySensorObserver::updateFrom_ = Update::Sensor
protected

◆ updatePose_

bool mc_observers::BodySensorObserver::updatePose_ = true
protected

◆ updateRobot_

std::string mc_observers::BodySensorObserver::updateRobot_
protected

◆ updateVel_

bool mc_observers::BodySensorObserver::updateVel_ = true
protected

◆ velW_

sva::MotionVecd mc_observers::BodySensorObserver::velW_ = sva::MotionVecd::Zero()
protected

The documentation for this struct was generated from the following file: