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

Controller implementation using GNC module. More...

#include <ctl_ros.h>

Public Types

enum  : ff_util::FSM::State { WAITING = 1, NOMINAL = 2, STOPPING = 3 }
 
enum  : ff_util::FSM::Event { GOAL_COMPLETE = (1<<0), GOAL_NOMINAL = (1<<1), GOAL_CANCEL = (1<<2), GOAL_STOP = (1<<3) }
 

Public Member Functions

 Ctl (ros::NodeHandle *nh, std::string const &name)
 
 ~Ctl ()
 
FSM::State Result (int32_t response)
 
bool EnableCtl (std_srvs::SetBoolRequest &req, std_srvs::SetBoolResponse &response)
 
void UpdateCallback (FSM::State const &state, FSM::Event const &event)
 
void EkfCallback (const ff_msgs::EkfState::ConstPtr &state)
 
void PoseCallback (const geometry_msgs::PoseStamped::ConstPtr &truth)
 
void TwistCallback (const geometry_msgs::TwistStamped::ConstPtr &truth)
 
void InertiaCallback (const geometry_msgs::InertiaStamped::ConstPtr &inertia)
 
void ControlTimerCallback (const ros::TimerEvent &event)
 
void FlightModeCallback (const ff_msgs::FlightMode::ConstPtr &mode)
 
void SetpointCallback (const ff_msgs::ControlState::ConstPtr &command)
 
void TimerCallback (const ros::TimerEvent &event)
 
void GoalCallback (ff_msgs::ControlGoalConstPtr const &control_goal)
 
void PreemptCallback ()
 
void CancelCallback ()
 
bool Command (uint8_t const mode, ff_msgs::ControlCommand const &poseVel=ff_msgs::ControlCommand())
 
bool Step (ros::Time curr_time)
 
void ReadParams (void)
 
std::string getName ()
 

Static Public Attributes

static constexpr double MAX_LATENCY = 0.5
 

Detailed Description

Controller implementation using GNC module.

Controller implementation using GNC module

Member Enumeration Documentation

◆ anonymous enum

anonymous enum : ff_util::FSM::State
Enumerator
WAITING 
NOMINAL 
STOPPING 

◆ anonymous enum

anonymous enum : ff_util::FSM::Event
Enumerator
GOAL_COMPLETE 
GOAL_NOMINAL 
GOAL_CANCEL 
GOAL_STOP 

Constructor & Destructor Documentation

◆ Ctl()

ctl::Ctl::Ctl ( ros::NodeHandle *  nh,
std::string const &  name 
)
explicit

Ctl allocate, register, initialize model

◆ ~Ctl()

ctl::Ctl::~Ctl ( )

destruct model

Member Function Documentation

◆ CancelCallback()

void ctl::Ctl::CancelCallback ( )

◆ Command()

bool ctl::Ctl::Command ( uint8_t const  mode,
ff_msgs::ControlCommand const &  poseVel = ff_msgs::ControlCommand() 
)

◆ ControlTimerCallback()

void ctl::Ctl::ControlTimerCallback ( const ros::TimerEvent &  event)

◆ EkfCallback()

void ctl::Ctl::EkfCallback ( const ff_msgs::EkfState::ConstPtr &  state)

◆ EnableCtl()

bool ctl::Ctl::EnableCtl ( std_srvs::SetBoolRequest &  req,
std_srvs::SetBoolResponse &  response 
)

◆ FlightModeCallback()

void ctl::Ctl::FlightModeCallback ( const ff_msgs::FlightMode::ConstPtr &  mode)

◆ getName()

std::string ctl::Ctl::getName ( )

◆ GoalCallback()

void ctl::Ctl::GoalCallback ( ff_msgs::ControlGoalConstPtr const &  control_goal)

◆ InertiaCallback()

void ctl::Ctl::InertiaCallback ( const geometry_msgs::InertiaStamped::ConstPtr &  inertia)

◆ PoseCallback()

void ctl::Ctl::PoseCallback ( const geometry_msgs::PoseStamped::ConstPtr &  truth)

◆ PreemptCallback()

void ctl::Ctl::PreemptCallback ( )

◆ ReadParams()

void ctl::Ctl::ReadParams ( void  )

◆ Result()

FSM::State ctl::Ctl::Result ( int32_t  response)

◆ SetpointCallback()

void ctl::Ctl::SetpointCallback ( const ff_msgs::ControlState::ConstPtr &  command)

◆ Step()

bool ctl::Ctl::Step ( ros::Time  curr_time)

◆ TimerCallback()

void ctl::Ctl::TimerCallback ( const ros::TimerEvent &  event)

◆ TwistCallback()

void ctl::Ctl::TwistCallback ( const geometry_msgs::TwistStamped::ConstPtr &  truth)

◆ UpdateCallback()

void ctl::Ctl::UpdateCallback ( FSM::State const &  state,
FSM::Event const &  event 
)

Member Data Documentation

◆ MAX_LATENCY

constexpr double ctl::Ctl::MAX_LATENCY = 0.5
staticconstexpr

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