NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
node_adders::CombinedNavStateNodeAdderModel Class Reference

#include <combined_nav_state_node_adder_model.h>

Inheritance diagram for node_adders::CombinedNavStateNodeAdderModel:
Inheritance graph

Public Types

using NodeType = localization_common::CombinedNavState
 
using NodesType = nodes::CombinedNavStateNodes
 
using MeasurementType = localization_measurements::ImuMeasurement
 
using Params = CombinedNavStateNodeAdderModelParams
 
using Base = MeasurementBasedTimestampedNodeAdderModel< MeasurementType, NodeType, NodesType >
 

Public Member Functions

 CombinedNavStateNodeAdderModel (const Params &params)
 
void AddPriors (const NodeType &node, const std::vector< gtsam::SharedNoiseModel > &noise_models, const localization_common::Time timestamp, const NodesType &nodes, gtsam::NonlinearFactorGraph &factors) const final
 
bool AddNodesAndRelativeFactors (const localization_common::Time timestamp_a, const localization_common::Time timestamp_b, NodesType &nodes, gtsam::NonlinearFactorGraph &factors) const final
 
bool AddRelativeFactors (const localization_common::Time timestamp_a, const localization_common::Time timestamp_b, const NodesType &nodes, gtsam::NonlinearFactorGraph &factors) const final
 
void AddMeasurement (const localization_measurements::ImuMeasurement &measurement) final
 
void RemoveMeasurements (const localization_common::Time oldest_allowed_time) final
 
bool CanAddNode (const localization_common::Time timestamp) const final
 
bool RemoveRelativeFactors (const localization_common::Time timestamp_a, const localization_common::Time timestamp_b, const NodesType &nodes, gtsam::NonlinearFactorGraph &factors) const final
 
void SetFanSpeedMode (const localization_measurements::FanSpeedMode &fan_speed_mode)
 
- Public Member Functions inherited from node_adders::MeasurementBasedTimestampedNodeAdderModel< localization_measurements::ImuMeasurement, localization_common::CombinedNavState, nodes::CombinedNavStateNodes >
 MeasurementBasedTimestampedNodeAdderModel (const TimestampedNodeAdderModelParams &params)
 
virtual ~MeasurementBasedTimestampedNodeAdderModel ()=default
 
- Public Member Functions inherited from node_adders::TimestampedNodeAdderModel< localization_common::CombinedNavState, nodes::CombinedNavStateNodes >
 TimestampedNodeAdderModel (const TimestampedNodeAdderModelParams &params)
 
virtual ~TimestampedNodeAdderModel ()=default
 

Friends

class boost::serialization::access
 

Additional Inherited Members

- Protected Attributes inherited from node_adders::TimestampedNodeAdderModel< localization_common::CombinedNavState, nodes::CombinedNavStateNodes >
TimestampedNodeAdderModelParams params_
 

Member Typedef Documentation

◆ Base

◆ MeasurementType

◆ NodesType

◆ NodeType

◆ Params

Constructor & Destructor Documentation

◆ CombinedNavStateNodeAdderModel()

node_adders::CombinedNavStateNodeAdderModel::CombinedNavStateNodeAdderModel ( const Params params)
explicit

Member Function Documentation

◆ AddMeasurement()

◆ AddNodesAndRelativeFactors()

bool node_adders::CombinedNavStateNodeAdderModel::AddNodesAndRelativeFactors ( const localization_common::Time  timestamp_a,
const localization_common::Time  timestamp_b,
NodesType nodes,
gtsam::NonlinearFactorGraph &  factors 
) const
finalvirtual

◆ AddPriors()

void node_adders::CombinedNavStateNodeAdderModel::AddPriors ( const NodeType node,
const std::vector< gtsam::SharedNoiseModel > &  noise_models,
const localization_common::Time  timestamp,
const NodesType nodes,
gtsam::NonlinearFactorGraph &  factors 
) const
finalvirtual

◆ AddRelativeFactors()

bool node_adders::CombinedNavStateNodeAdderModel::AddRelativeFactors ( const localization_common::Time  timestamp_a,
const localization_common::Time  timestamp_b,
const NodesType nodes,
gtsam::NonlinearFactorGraph &  factors 
) const
finalvirtual

◆ CanAddNode()

bool node_adders::CombinedNavStateNodeAdderModel::CanAddNode ( const localization_common::Time  timestamp) const
finalvirtual

◆ RemoveMeasurements()

◆ RemoveRelativeFactors()

bool node_adders::CombinedNavStateNodeAdderModel::RemoveRelativeFactors ( const localization_common::Time  timestamp_a,
const localization_common::Time  timestamp_b,
const NodesType nodes,
gtsam::NonlinearFactorGraph &  factors 
) const
finalvirtual

◆ SetFanSpeedMode()

void node_adders::CombinedNavStateNodeAdderModel::SetFanSpeedMode ( const localization_measurements::FanSpeedMode fan_speed_mode)

Friends And Related Function Documentation

◆ boost::serialization::access

friend class boost::serialization::access
friend

The documentation for this class was generated from the following files: