NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
node_adders::MeasurementBasedTimestampedNodeAdder< MeasurementType, NodeType, TimestampedNodesType, MeasurementBasedTimestampedNodeAdderModelType > Class Template Reference

#include <measurement_based_timestamped_node_adder.h>

Inheritance diagram for node_adders::MeasurementBasedTimestampedNodeAdder< MeasurementType, NodeType, TimestampedNodesType, MeasurementBasedTimestampedNodeAdderModelType >:
Inheritance graph

Public Types

using Params = TimestampedNodeAdderParams< NodeType >
 

Public Member Functions

 MeasurementBasedTimestampedNodeAdder (const Params &params, const typename MeasurementBasedTimestampedNodeAdderModelType::Params &node_adder_model_params, std::shared_ptr< nodes::Values > values)
 
 MeasurementBasedTimestampedNodeAdder (const Params &params, const typename MeasurementBasedTimestampedNodeAdderModelType::Params &node_adder_model_params, std::shared_ptr< TimestampedNodesType > timestamped_nodes)
 
void AddMeasurement (const MeasurementType &measurement)
 
void RemoveMeasurements (const localization_common::Time oldest_allowed_time)
 
bool SlideWindow (const localization_common::Time oldest_allowed_timestamp, const boost::optional< const gtsam::Marginals & > &marginals, const gtsam::KeyVector &old_keys, const double huber_k, gtsam::NonlinearFactorGraph &factors) final
 
- Public Member Functions inherited from node_adders::TimestampedNodeAdder< NodeType, TimestampedNodesType, MeasurementBasedTimestampedNodeAdderModelType >
 TimestampedNodeAdder (const TimestampedNodeAdderParams< NodeType > &params, const typename MeasurementBasedTimestampedNodeAdderModelType ::Params &node_adder_model_params, std::shared_ptr< nodes::Values > values)
 
 TimestampedNodeAdder (const TimestampedNodeAdderParams< NodeType > &params, const typename MeasurementBasedTimestampedNodeAdderModelType ::Params &node_adder_model_params, std::shared_ptr< TimestampedNodesType > timestamped_nodes)
 
 TimestampedNodeAdder ()=default
 
virtual ~TimestampedNodeAdder ()=default
 
void AddInitialNodesAndPriors (gtsam::NonlinearFactorGraph &factors) final
 
void AddInitialNodesAndPriors (const NodeType &initial_node, const std::vector< gtsam::SharedNoiseModel > &initial_noise, const localization_common::Time timestamp, gtsam::NonlinearFactorGraph &factors)
 
bool AddNode (const localization_common::Time timestamp, gtsam::NonlinearFactorGraph &factors) final
 
bool SlideWindow (const localization_common::Time oldest_allowed_timestamp, const boost::optional< const gtsam::Marginals & > &marginals, const gtsam::KeyVector &old_keys, const double huber_k, gtsam::NonlinearFactorGraph &factors) override
 
boost::optional< localization_common::TimeSlideWindowNewStartTime () const final
 
gtsam::KeyVector OldKeys (const localization_common::Time oldest_allowed_time, const gtsam::NonlinearFactorGraph &graph) const final
 
boost::optional< localization_common::TimeStartTime () const final
 
boost::optional< localization_common::TimeEndTime () const final
 
bool CanAddNode (const localization_common::Time timestamp) const final
 
gtsam::KeyVector Keys (const localization_common::Time timestamp) const final
 
const TimestampedNodesType & nodes () const
 
std::shared_ptr< const TimestampedNodesType > nodes_ptr ()
 
MeasurementBasedTimestampedNodeAdderModelType & node_adder_model ()
 
- Public Member Functions inherited from node_adders::SlidingWindowNodeAdder
virtual ~SlidingWindowNodeAdder ()
 
virtual boost::optional< localization_common::TimeSlideWindowNewStartTime () const =0
 
virtual boost::optional< localization_common::TimeStartTime () const =0
 
virtual boost::optional< localization_common::TimeEndTime () const =0
 
- Public Member Functions inherited from node_adders::NodeAdder
virtual ~NodeAdder ()
 

Friends

class boost::serialization::access
 

Member Typedef Documentation

◆ Params

template<typename MeasurementType , typename NodeType , typename TimestampedNodesType , typename MeasurementBasedTimestampedNodeAdderModelType >
using node_adders::MeasurementBasedTimestampedNodeAdder< MeasurementType, NodeType, TimestampedNodesType, MeasurementBasedTimestampedNodeAdderModelType >::Params = TimestampedNodeAdderParams<NodeType>

Constructor & Destructor Documentation

◆ MeasurementBasedTimestampedNodeAdder() [1/2]

template<typename MeasurementType , typename NodeType , typename TimestampedNodesType , typename MeasurementBasedTimestampedNodeAdderModelType >
node_adders::MeasurementBasedTimestampedNodeAdder< MeasurementType, NodeType, TimestampedNodesType, MeasurementBasedTimestampedNodeAdderModelType >::MeasurementBasedTimestampedNodeAdder ( const Params params,
const typename MeasurementBasedTimestampedNodeAdderModelType::Params &  node_adder_model_params,
std::shared_ptr< nodes::Values values 
)

◆ MeasurementBasedTimestampedNodeAdder() [2/2]

template<typename MeasurementType , typename NodeType , typename TimestampedNodesType , typename MeasurementBasedTimestampedNodeAdderModelType >
node_adders::MeasurementBasedTimestampedNodeAdder< MeasurementType, NodeType, TimestampedNodesType, MeasurementBasedTimestampedNodeAdderModelType >::MeasurementBasedTimestampedNodeAdder ( const Params params,
const typename MeasurementBasedTimestampedNodeAdderModelType::Params &  node_adder_model_params,
std::shared_ptr< TimestampedNodesType >  timestamped_nodes 
)

Member Function Documentation

◆ AddMeasurement()

template<typename MeasurementType , typename NodeType , typename TimestampedNodesType , typename MeasurementBasedTimestampedNodeAdderModelType >
void node_adders::MeasurementBasedTimestampedNodeAdder< MeasurementType, NodeType, TimestampedNodesType, MeasurementBasedTimestampedNodeAdderModelType >::AddMeasurement ( const MeasurementType &  measurement)

◆ RemoveMeasurements()

template<typename MeasurementType , typename NodeType , typename TimestampedNodesType , typename MeasurementBasedTimestampedNodeAdderModelType >
void node_adders::MeasurementBasedTimestampedNodeAdder< MeasurementType, NodeType, TimestampedNodesType, MeasurementBasedTimestampedNodeAdderModelType >::RemoveMeasurements ( const localization_common::Time  oldest_allowed_time)

◆ SlideWindow()

template<typename MeasurementType , typename NodeType , typename TimestampedNodesType , typename MeasurementBasedTimestampedNodeAdderModelType >
bool node_adders::MeasurementBasedTimestampedNodeAdder< MeasurementType, NodeType, TimestampedNodesType, MeasurementBasedTimestampedNodeAdderModelType >::SlideWindow ( const localization_common::Time  oldest_allowed_timestamp,
const boost::optional< const gtsam::Marginals & > &  marginals,
const gtsam::KeyVector &  old_keys,
const double  huber_k,
gtsam::NonlinearFactorGraph &  factors 
)
finalvirtual

Friends And Related Function Documentation

◆ boost::serialization::access

template<typename MeasurementType , typename NodeType , typename TimestampedNodesType , typename MeasurementBasedTimestampedNodeAdderModelType >
friend class boost::serialization::access
friend

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