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

Force Allocation Module implementation using GNC module. More...

#include <fam.h>

Public Member Functions

 Fam (ros::NodeHandle *nh)
 
 ~Fam ()
 
void Step ()
 

Protected Member Functions

void ReadParams (void)
 
void CtlCallBack (const ff_msgs::FamCommand &c)
 
void FlightModeCallback (const ff_msgs::FlightMode::ConstPtr &mode)
 
void InertiaCallback (const geometry_msgs::InertiaStamped::ConstPtr &inertia)
 

Protected Attributes

pmc::Fam fam_
 
ros::Subscriber ctl_sub_
 
ros::Subscriber flight_mode_sub_
 
ros::Subscriber inertia_sub_
 
ros::Publisher pmc_pub_
 
ff_util::PerfTimer pt_fam_
 
std::mutex mutex_speed_
 
std::mutex mutex_mass_
 
Eigen::Vector3f center_of_mass_
 
bool inertia_received_
 
pmc::FamInput input_
 

Detailed Description

Force Allocation Module implementation using GNC module.

Constructor & Destructor Documentation

◆ Fam()

fam::Fam::Fam ( ros::NodeHandle *  nh)
explicit

◆ ~Fam()

fam::Fam::~Fam ( )

Member Function Documentation

◆ CtlCallBack()

void fam::Fam::CtlCallBack ( const ff_msgs::FamCommand &  c)
protected

◆ FlightModeCallback()

void fam::Fam::FlightModeCallback ( const ff_msgs::FlightMode::ConstPtr &  mode)
protected

◆ InertiaCallback()

void fam::Fam::InertiaCallback ( const geometry_msgs::InertiaStamped::ConstPtr &  inertia)
protected

◆ ReadParams()

void fam::Fam::ReadParams ( void  )
protected

◆ Step()

void fam::Fam::Step ( )

Member Data Documentation

◆ center_of_mass_

Eigen::Vector3f fam::Fam::center_of_mass_
protected

◆ ctl_sub_

ros::Subscriber fam::Fam::ctl_sub_
protected

◆ fam_

pmc::Fam fam::Fam::fam_
protected

◆ flight_mode_sub_

ros::Subscriber fam::Fam::flight_mode_sub_
protected

◆ inertia_received_

bool fam::Fam::inertia_received_
protected

◆ inertia_sub_

ros::Subscriber fam::Fam::inertia_sub_
protected

◆ input_

pmc::FamInput fam::Fam::input_
protected

◆ mutex_mass_

std::mutex fam::Fam::mutex_mass_
protected

◆ mutex_speed_

std::mutex fam::Fam::mutex_speed_
protected

◆ pmc_pub_

ros::Publisher fam::Fam::pmc_pub_
protected

◆ pt_fam_

ff_util::PerfTimer fam::Fam::pt_fam_
protected

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