NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
#include <executive.h>
Public Member Functions | |
Executive () | |
~Executive () | |
void | CameraStatesCallback (ff_msgs::CameraStatesStampedConstPtr const &state) |
void | CmdCallback (ff_msgs::CommandStampedPtr const &cmd) |
void | DataToDiskCallback (ff_msgs::CompressedFileConstPtr const &data) |
void | DockStateCallback (ff_msgs::DockStateConstPtr const &state) |
void | FaultStateCallback (ff_msgs::FaultStateConstPtr const &state) |
void | GuestScienceAckCallback (ff_msgs::AckStampedConstPtr const &ack) |
void | GuestScienceConfigCallback (ff_msgs::GuestScienceConfigConstPtr const &config) |
void | GuestScienceStateCallback (ff_msgs::GuestScienceStateConstPtr const &state) |
void | GuestScienceCustomCmdTimeoutCallback (ros::TimerEvent const &te) |
void | GuestScienceStartStopRestartCmdTimeoutCallback (ros::TimerEvent const &te) |
void | InertiaCallback (geometry_msgs::InertiaStampedConstPtr const &inertia) |
void | LedConnectedCallback () |
void | MotionStateCallback (ff_msgs::MotionStatePtr const &state) |
void | PerchStateCallback (ff_msgs::PerchStateConstPtr const &state) |
void | PlanCallback (ff_msgs::CompressedFileConstPtr const &plan) |
void | SysMonitorHeartbeatCallback (ff_msgs::HeartbeatConstPtr const &heartbeat) |
void | SysMonitorTimeoutCallback (ros::TimerEvent const &te) |
void | WaitCallback (ros::TimerEvent const &te) |
void | ZonesCallback (ff_msgs::CompressedFileConstPtr const &zones) |
bool | AreActionsRunning () |
void | CancelAction (Action action, std::string cmd) |
bool | FillArmGoal (ff_msgs::CommandStampedPtr const &cmd) |
bool | FillDockGoal (ff_msgs::CommandStampedPtr const &cmd, bool return_to_dock) |
bool | FillMotionGoal (Action action, ff_msgs::CommandStampedPtr const &cmd=nullptr) |
bool | IsActionRunning (Action action) |
bool | StartAction (Action action, std::string const &cmd_id) |
bool | RemoveAction (Action action) |
void | ArmResultCallback (ff_util::FreeFlyerActionState::Enum const &state, ff_msgs::ArmResultConstPtr const &result) |
void | DockResultCallback (ff_util::FreeFlyerActionState::Enum const &state, ff_msgs::DockResultConstPtr const &result) |
void | LocalizationResultCallback (ff_util::FreeFlyerActionState::Enum const &state, ff_msgs::LocalizationResultConstPtr const &result) |
void | MotionFeedbackCallback (ff_msgs::MotionFeedbackConstPtr const &feedback) |
void | MotionResultCallback (ff_util::FreeFlyerActionState::Enum const &state, ff_msgs::MotionResultConstPtr const &result) |
void | PerchResultCallback (ff_util::FreeFlyerActionState::Enum const &state, ff_msgs::PerchResultConstPtr const &result) |
void | PublishCmdAck (std::string const &cmd_id, uint8_t completed_status=ff_msgs::AckCompletedStatus::OK, std::string const &message="", uint8_t status=ff_msgs::AckStatus::COMPLETED) |
void | PublishPlan () |
void | PublishPlanStatus (uint8_t status) |
ff_msgs::MobilityState | GetMobilityState () |
uint8_t | GetPlanExecState () |
std::string | GetRunPlanCmdId () |
void | SetMobilityState () |
void | SetMobilityState (uint8_t state, uint32_t sub_state=0) |
void | SetOpState (OpState *state) |
void | SetPlanExecState (uint8_t state) |
void | SetRunPlanCmdId (std::string cmd_id) |
void | AckMobilityStateIssue (ff_msgs::CommandStampedPtr const &cmd, std::string const ¤t_mobility_state, std::string const &accepted_mobility_state="") |
bool | ArmControl (ff_msgs::CommandStampedPtr const &cmd) |
bool | CheckServiceExists (ros::ServiceClient &serviceIn, std::string const &serviceName, std::string const &cmd_in) |
bool | CheckStoppedOrDrifting (std::string const &cmd_id, std::string const &cmd_name) |
bool | ConfigureLed (ff_hw_msgs::ConfigureSystemLeds &led_srv) |
bool | ConfigureMobility (bool move_to_start, std::string &err_msg) |
bool | FailCommandIfMoving (ff_msgs::CommandStampedPtr const &cmd) |
bool | LoadUnloadNodelet (ff_msgs::CommandStampedPtr const &cmd) |
ros::Time | MsToSec (std::string timestamp) |
bool | PowerItem (ff_msgs::CommandStampedPtr const &cmd, bool on) |
bool | ProcessGuestScienceCommand (ff_msgs::CommandStampedPtr const &cmd) |
bool | ResetEkf (std::string const &cmd_id) |
void | StartWaitTimer (float duration) |
void | StopWaitTimer () |
bool | AckCurrentPlanItem () |
sequencer::ItemType | GetCurrentPlanItemType () |
ff_msgs::CommandStampedPtr | GetPlanCommand () |
bool | GetSetPlanInertia (std::string const &cmd_id) |
void | GetSetPlanOperatingLimits () |
bool | ArmPanAndTilt (ff_msgs::CommandStampedPtr const &cmd) |
bool | AutoReturn (ff_msgs::CommandStampedPtr const &cmd) |
bool | CustomGuestScience (ff_msgs::CommandStampedPtr const &cmd) |
bool | DeployArm (ff_msgs::CommandStampedPtr const &cmd) |
bool | Dock (ff_msgs::CommandStampedPtr const &cmd) |
bool | EnableAstrobeeIntercomms (ff_msgs::CommandStampedPtr const &cmd) |
bool | Fault (ff_msgs::CommandStampedPtr const &cmd) |
bool | GripperControl (ff_msgs::CommandStampedPtr const &cmd) |
bool | IdlePropulsion (ff_msgs::CommandStampedPtr const &cmd) |
bool | InitializeBias (ff_msgs::CommandStampedPtr const &cmd) |
bool | LoadNodelet (ff_msgs::CommandStampedPtr const &cmd) |
bool | NoOp (ff_msgs::CommandStampedPtr const &cmd) |
bool | PausePlan (ff_msgs::CommandStampedPtr const &cmd) |
bool | Perch (ff_msgs::CommandStampedPtr const &cmd) |
bool | PowerItemOff (ff_msgs::CommandStampedPtr const &cmd) |
bool | PowerItemOn (ff_msgs::CommandStampedPtr const &cmd) |
bool | Prepare (ff_msgs::CommandStampedPtr const &cmd) |
bool | ReacquirePosition (ff_msgs::CommandStampedPtr const &cmd) |
bool | ResetEkf (ff_msgs::CommandStampedPtr const &cmd) |
bool | RestartGuestScience (ff_msgs::CommandStampedPtr const &cmd) |
bool | RunPlan (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetCamera (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetCameraRecording (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetCameraStreaming (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetCheckObstacles (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetCheckZones (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetDataToDisk (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetEnableAutoReturn (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetEnableImmediate (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetEnableReplan (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetExposure (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetFlashlightBrightness (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetHolonomicMode (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetInertia (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetMap (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetOperatingLimits (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetPlan (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetPlanner (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetTelemetryRate (ff_msgs::CommandStampedPtr const &cmd) |
bool | SetZones (ff_msgs::CommandStampedPtr const &cmd) |
bool | SkipPlanStep (ff_msgs::CommandStampedPtr const &cmd) |
bool | StartGuestScience (ff_msgs::CommandStampedPtr const &cmd) |
bool | StartRecording (ff_msgs::CommandStampedPtr const &cmd) |
bool | StopAllMotion (ff_msgs::CommandStampedPtr const &cmd) |
bool | StopArm (ff_msgs::CommandStampedPtr const &cmd) |
bool | StopRecording (ff_msgs::CommandStampedPtr const &cmd) |
bool | StopGuestScience (ff_msgs::CommandStampedPtr const &cmd) |
bool | StowArm (ff_msgs::CommandStampedPtr const &cmd) |
bool | SwitchLocalization (ff_msgs::CommandStampedPtr const &cmd) |
bool | Undock (ff_msgs::CommandStampedPtr const &cmd) |
bool | UnloadNodelet (ff_msgs::CommandStampedPtr const &cmd) |
bool | Unperch (ff_msgs::CommandStampedPtr const &cmd) |
bool | Unterminate (ff_msgs::CommandStampedPtr const &cmd) |
bool | Wait (ff_msgs::CommandStampedPtr const &cmd) |
Public Member Functions inherited from ff_util::FreeFlyerNodelet | |
FreeFlyerNodelet (bool autostart_hb_timer=true) | |
FreeFlyerNodelet (std::string const &name, bool autostart_hb_timer=true) | |
virtual | ~FreeFlyerNodelet () |
void | AssertFault (FaultKeys enum_key, std::string const &message, ros::Time time_fault_occurred=ros::Time::now()) |
void | ClearAllFaults () |
void | ClearFault (FaultKeys enum_key) |
void | PrintFaults () |
ros::NodeHandle * | GetPlatformHandle (bool multithreaded=false) |
ros::NodeHandle * | GetPrivateHandle (bool multithreaded=false) |
std::string | GetName () |
std::string | GetPlatform () |
std::string | GetTransform (std::string const &child) |
Protected Member Functions | |
virtual void | Initialize (ros::NodeHandle *nh) |
bool | ReadParams () |
bool | ReadMapperParams () |
bool | ReadCommand (config_reader::ConfigReader::Table *response, ff_msgs::CommandStampedPtr cmd) |
void | PublishAgentState () |
Protected Member Functions inherited from ff_util::FreeFlyerNodelet | |
virtual void | Reset () |
virtual void | Sleep () |
virtual void | Wakeup () |
void | StopHeartbeat () |
void | SendDiagnostics (const std::vector< diagnostic_msgs::KeyValue > &keyval) |
void | Setup (ros::NodeHandle &nh, ros::NodeHandle &nh_mt, std::string plugin_name) |
Additional Inherited Members | |
Public Types inherited from ff_util::FreeFlyerNodelet | |
enum | ResolveType : uint8_t { NAMESPACE = 0, TRANSFORM = 1, RESOURCE = 1 } |
Executive class is the mediator, responsible for receiving broadcasted messages and forwarding to specific nodes.
Decisions are handled through current executing state
ref: state & mediator design pattern
executive::Executive::Executive | ( | ) |
executive::Executive::~Executive | ( | ) |
bool executive::Executive::AckCurrentPlanItem | ( | ) |
void executive::Executive::AckMobilityStateIssue | ( | ff_msgs::CommandStampedPtr const & | cmd, |
std::string const & | current_mobility_state, | ||
std::string const & | accepted_mobility_state = "" |
||
) |
bool executive::Executive::AreActionsRunning | ( | ) |
bool executive::Executive::ArmControl | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::ArmPanAndTilt | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::ArmResultCallback | ( | ff_util::FreeFlyerActionState::Enum const & | state, |
ff_msgs::ArmResultConstPtr const & | result | ||
) |
bool executive::Executive::AutoReturn | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::CameraStatesCallback | ( | ff_msgs::CameraStatesStampedConstPtr const & | state | ) |
void executive::Executive::CancelAction | ( | Action | action, |
std::string | cmd | ||
) |
bool executive::Executive::CheckServiceExists | ( | ros::ServiceClient & | serviceIn, |
std::string const & | serviceName, | ||
std::string const & | cmd_in | ||
) |
bool executive::Executive::CheckStoppedOrDrifting | ( | std::string const & | cmd_id, |
std::string const & | cmd_name | ||
) |
void executive::Executive::CmdCallback | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::ConfigureLed | ( | ff_hw_msgs::ConfigureSystemLeds & | led_srv | ) |
bool executive::Executive::ConfigureMobility | ( | bool | move_to_start, |
std::string & | err_msg | ||
) |
bool executive::Executive::CustomGuestScience | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::DataToDiskCallback | ( | ff_msgs::CompressedFileConstPtr const & | data | ) |
bool executive::Executive::DeployArm | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::Dock | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::DockResultCallback | ( | ff_util::FreeFlyerActionState::Enum const & | state, |
ff_msgs::DockResultConstPtr const & | result | ||
) |
void executive::Executive::DockStateCallback | ( | ff_msgs::DockStateConstPtr const & | state | ) |
bool executive::Executive::EnableAstrobeeIntercomms | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::FailCommandIfMoving | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::Fault | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::FaultStateCallback | ( | ff_msgs::FaultStateConstPtr const & | state | ) |
bool executive::Executive::FillArmGoal | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::FillDockGoal | ( | ff_msgs::CommandStampedPtr const & | cmd, |
bool | return_to_dock | ||
) |
bool executive::Executive::FillMotionGoal | ( | Action | action, |
ff_msgs::CommandStampedPtr const & | cmd = nullptr |
||
) |
sequencer::ItemType executive::Executive::GetCurrentPlanItemType | ( | ) |
ff_msgs::MobilityState executive::Executive::GetMobilityState | ( | ) |
ff_msgs::CommandStampedPtr executive::Executive::GetPlanCommand | ( | ) |
uint8_t executive::Executive::GetPlanExecState | ( | ) |
std::string executive::Executive::GetRunPlanCmdId | ( | ) |
bool executive::Executive::GetSetPlanInertia | ( | std::string const & | cmd_id | ) |
void executive::Executive::GetSetPlanOperatingLimits | ( | ) |
bool executive::Executive::GripperControl | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::GuestScienceAckCallback | ( | ff_msgs::AckStampedConstPtr const & | ack | ) |
void executive::Executive::GuestScienceConfigCallback | ( | ff_msgs::GuestScienceConfigConstPtr const & | config | ) |
void executive::Executive::GuestScienceCustomCmdTimeoutCallback | ( | ros::TimerEvent const & | te | ) |
void executive::Executive::GuestScienceStartStopRestartCmdTimeoutCallback | ( | ros::TimerEvent const & | te | ) |
void executive::Executive::GuestScienceStateCallback | ( | ff_msgs::GuestScienceStateConstPtr const & | state | ) |
bool executive::Executive::IdlePropulsion | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::InertiaCallback | ( | geometry_msgs::InertiaStampedConstPtr const & | inertia | ) |
|
protectedvirtual |
Reimplemented from ff_util::FreeFlyerNodelet.
bool executive::Executive::InitializeBias | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::IsActionRunning | ( | Action | action | ) |
void executive::Executive::LedConnectedCallback | ( | ) |
bool executive::Executive::LoadNodelet | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::LoadUnloadNodelet | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::LocalizationResultCallback | ( | ff_util::FreeFlyerActionState::Enum const & | state, |
ff_msgs::LocalizationResultConstPtr const & | result | ||
) |
void executive::Executive::MotionFeedbackCallback | ( | ff_msgs::MotionFeedbackConstPtr const & | feedback | ) |
void executive::Executive::MotionResultCallback | ( | ff_util::FreeFlyerActionState::Enum const & | state, |
ff_msgs::MotionResultConstPtr const & | result | ||
) |
void executive::Executive::MotionStateCallback | ( | ff_msgs::MotionStatePtr const & | state | ) |
ros::Time executive::Executive::MsToSec | ( | std::string | timestamp | ) |
bool executive::Executive::NoOp | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::PausePlan | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::Perch | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::PerchResultCallback | ( | ff_util::FreeFlyerActionState::Enum const & | state, |
ff_msgs::PerchResultConstPtr const & | result | ||
) |
void executive::Executive::PerchStateCallback | ( | ff_msgs::PerchStateConstPtr const & | state | ) |
void executive::Executive::PlanCallback | ( | ff_msgs::CompressedFileConstPtr const & | plan | ) |
bool executive::Executive::PowerItem | ( | ff_msgs::CommandStampedPtr const & | cmd, |
bool | on | ||
) |
bool executive::Executive::PowerItemOff | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::PowerItemOn | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::Prepare | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::ProcessGuestScienceCommand | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
|
protected |
void executive::Executive::PublishCmdAck | ( | std::string const & | cmd_id, |
uint8_t | completed_status = ff_msgs::AckCompletedStatus::OK , |
||
std::string const & | message = "" , |
||
uint8_t | status = ff_msgs::AckStatus::COMPLETED |
||
) |
void executive::Executive::PublishPlan | ( | ) |
void executive::Executive::PublishPlanStatus | ( | uint8_t | status | ) |
bool executive::Executive::ReacquirePosition | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
|
protected |
|
protected |
|
protected |
bool executive::Executive::RemoveAction | ( | Action | action | ) |
bool executive::Executive::ResetEkf | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::ResetEkf | ( | std::string const & | cmd_id | ) |
bool executive::Executive::RestartGuestScience | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::RunPlan | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetCamera | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetCameraRecording | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetCameraStreaming | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetCheckObstacles | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetCheckZones | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetDataToDisk | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetEnableAutoReturn | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetEnableImmediate | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetEnableReplan | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetExposure | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetFlashlightBrightness | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetHolonomicMode | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetInertia | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetMap | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::SetMobilityState | ( | ) |
void executive::Executive::SetMobilityState | ( | uint8_t | state, |
uint32_t | sub_state = 0 |
||
) |
bool executive::Executive::SetOperatingLimits | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::SetOpState | ( | OpState * | state | ) |
bool executive::Executive::SetPlan | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::SetPlanExecState | ( | uint8_t | state | ) |
bool executive::Executive::SetPlanner | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::SetRunPlanCmdId | ( | std::string | cmd_id | ) |
bool executive::Executive::SetTelemetryRate | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SetZones | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SkipPlanStep | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::StartAction | ( | Action | action, |
std::string const & | cmd_id | ||
) |
bool executive::Executive::StartGuestScience | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::StartRecording | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::StartWaitTimer | ( | float | duration | ) |
bool executive::Executive::StopAllMotion | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::StopArm | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::StopGuestScience | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::StopRecording | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::StopWaitTimer | ( | ) |
bool executive::Executive::StowArm | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::SwitchLocalization | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::SysMonitorHeartbeatCallback | ( | ff_msgs::HeartbeatConstPtr const & | heartbeat | ) |
void executive::Executive::SysMonitorTimeoutCallback | ( | ros::TimerEvent const & | te | ) |
bool executive::Executive::Undock | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::UnloadNodelet | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::Unperch | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::Unterminate | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
bool executive::Executive::Wait | ( | ff_msgs::CommandStampedPtr const & | cmd | ) |
void executive::Executive::WaitCallback | ( | ros::TimerEvent const & | te | ) |
void executive::Executive::ZonesCallback | ( | ff_msgs::CompressedFileConstPtr const & | zones | ) |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |