|
enum | : FSM::Event {
READY = (1<<0),
GOAL_EXEC = (1<<1),
GOAL_MOVE = (1<<2),
GOAL_STOP = (1<<3),
GOAL_IDLE = (1<<4),
GOAL_PREP = (1<<5),
GOAL_CANCEL = (1<<6),
PLAN_SUCCESS = (1<<7),
PLAN_FAILED = (1<<8),
PMC_READY = (1<<9),
PMC_TIMEOUT = (1<<10),
CONTROL_SUCCESS = (1<<11),
CONTROL_FAILED = (1<<12),
TOLERANCE_POS_ENDPOINT = (1<<13),
TOLERANCE_POS = (1<<14),
TOLERANCE_ATT = (1<<15),
TOLERANCE_VEL = (1<<16),
TOLERANCE_OMEGA = (1<<17),
OBSTACLE_DETECTED = (1<<18),
MANUAL_STATE_SET = (1<<19),
REPLAN_TIMEOUT = (1<<20)
} |
|
enum | ControlType { IDLE,
STOP,
NOMINAL
} |
|
enum | ResolveType : uint8_t { NAMESPACE = 0,
TRANSFORM = 1,
RESOURCE = 1
} |
|
|
void | Initialize (ros::NodeHandle *nh) |
|
bool | ReconfigureCallback (dynamic_reconfigure::Config &config) |
|
void | ConnectedCallback () |
|
bool | SetStateCallback (ff_msgs::SetState::Request &req, ff_msgs::SetState::Response &res) |
|
bool | SetInertiaCallback (ff_msgs::SetInertia::Request &req, ff_msgs::SetInertia::Response &res) |
|
bool | PlannerRegisterCallback (ff_msgs::RegisterPlanner::Request &req, ff_msgs::RegisterPlanner::Response &res) |
|
int32_t | ValidateResult (int validator_response) |
|
int32_t | Result (int32_t response) |
|
bool | GetRobotPose (geometry_msgs::PoseStamped &pose) |
|
void | UpdateCallback (FSM::State const &state, FSM::Event const &event) |
|
void | HazardCallback (ff_msgs::Hazard::ConstPtr const &msg) |
|
bool | Plan (std::vector< geometry_msgs::PoseStamped > const &states, ros::Duration duration=ros::Duration(0)) |
|
void | PFeedbackCallback (ff_msgs::PlanFeedbackConstPtr const &feedback) |
|
void | PResultCallback (ff_util::FreeFlyerActionState::Enum result_code, ff_msgs::PlanResultConstPtr const &result) |
|
void | ReplanCallback (const ros::TimerEvent &) |
|
bool | FlightMode () |
|
void | PmcStateCallback (ff_hw_msgs::PmcState::ConstPtr const &msg) |
|
void | PmcTimeout (const ros::TimerEvent &) |
|
void | FeedbackCallback (const ros::TimerEvent &) |
|
bool | Control (ControlType type, ff_util::Segment const &segment=ff_util::Segment()) |
|
void | CFeedbackCallback (ff_msgs::ControlFeedbackConstPtr const &feedback) |
|
void | CResultCallback (ff_util::FreeFlyerActionState::Enum result_code, ff_msgs::ControlResultConstPtr const &result) |
|
void | GoalCallback (ff_msgs::MotionGoalConstPtr const &goal) |
|
void | PreemptCallback () |
|
void | CancelCallback () |
|
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) |
|
|
std::map< std::string, int > | faults_ |
|
◆ anonymous enum
Enumerator |
---|
READY | |
GOAL_EXEC | |
GOAL_MOVE | |
GOAL_STOP | |
GOAL_IDLE | |
GOAL_PREP | |
GOAL_CANCEL | |
PLAN_SUCCESS | |
PLAN_FAILED | |
PMC_READY | |
PMC_TIMEOUT | |
CONTROL_SUCCESS | |
CONTROL_FAILED | |
TOLERANCE_POS_ENDPOINT | |
TOLERANCE_POS | |
TOLERANCE_ATT | |
TOLERANCE_VEL | |
TOLERANCE_OMEGA | |
OBSTACLE_DETECTED | |
MANUAL_STATE_SET | |
REPLAN_TIMEOUT | |
◆ ControlType
Enumerator |
---|
IDLE | |
STOP | |
NOMINAL | |
◆ ChoreographerNodelet()
choreographer::ChoreographerNodelet::ChoreographerNodelet |
( |
| ) |
|
|
inline |
◆ ~ChoreographerNodelet()
choreographer::ChoreographerNodelet::~ChoreographerNodelet |
( |
| ) |
|
|
inline |
◆ CancelCallback()
void choreographer::ChoreographerNodelet::CancelCallback |
( |
| ) |
|
|
inlineprotected |
◆ CFeedbackCallback()
void choreographer::ChoreographerNodelet::CFeedbackCallback |
( |
ff_msgs::ControlFeedbackConstPtr const & |
feedback | ) |
|
|
inlineprotected |
◆ ConnectedCallback()
void choreographer::ChoreographerNodelet::ConnectedCallback |
( |
| ) |
|
|
inlineprotected |
◆ Control()
◆ CResultCallback()
◆ FeedbackCallback()
void choreographer::ChoreographerNodelet::FeedbackCallback |
( |
const ros::TimerEvent & |
| ) |
|
|
inlineprotected |
◆ FlightMode()
bool choreographer::ChoreographerNodelet::FlightMode |
( |
| ) |
|
|
inlineprotected |
◆ GetRobotPose()
bool choreographer::ChoreographerNodelet::GetRobotPose |
( |
geometry_msgs::PoseStamped & |
pose | ) |
|
|
inlineprotected |
◆ GoalCallback()
void choreographer::ChoreographerNodelet::GoalCallback |
( |
ff_msgs::MotionGoalConstPtr const & |
goal | ) |
|
|
inlineprotected |
◆ HazardCallback()
void choreographer::ChoreographerNodelet::HazardCallback |
( |
ff_msgs::Hazard::ConstPtr const & |
msg | ) |
|
|
inlineprotected |
◆ Initialize()
void choreographer::ChoreographerNodelet::Initialize |
( |
ros::NodeHandle * |
nh | ) |
|
|
inlineprotectedvirtual |
◆ PFeedbackCallback()
void choreographer::ChoreographerNodelet::PFeedbackCallback |
( |
ff_msgs::PlanFeedbackConstPtr const & |
feedback | ) |
|
|
inlineprotected |
◆ Plan()
bool choreographer::ChoreographerNodelet::Plan |
( |
std::vector< geometry_msgs::PoseStamped > const & |
states, |
|
|
ros::Duration |
duration = ros::Duration(0) |
|
) |
| |
|
inlineprotected |
◆ PlannerRegisterCallback()
bool choreographer::ChoreographerNodelet::PlannerRegisterCallback |
( |
ff_msgs::RegisterPlanner::Request & |
req, |
|
|
ff_msgs::RegisterPlanner::Response & |
res |
|
) |
| |
|
inlineprotected |
◆ PmcStateCallback()
void choreographer::ChoreographerNodelet::PmcStateCallback |
( |
ff_hw_msgs::PmcState::ConstPtr const & |
msg | ) |
|
|
inlineprotected |
◆ PmcTimeout()
void choreographer::ChoreographerNodelet::PmcTimeout |
( |
const ros::TimerEvent & |
| ) |
|
|
inlineprotected |
◆ PreemptCallback()
void choreographer::ChoreographerNodelet::PreemptCallback |
( |
| ) |
|
|
inlineprotected |
◆ PResultCallback()
◆ ReconfigureCallback()
bool choreographer::ChoreographerNodelet::ReconfigureCallback |
( |
dynamic_reconfigure::Config & |
config | ) |
|
|
inlineprotected |
◆ ReplanCallback()
void choreographer::ChoreographerNodelet::ReplanCallback |
( |
const ros::TimerEvent & |
| ) |
|
|
inlineprotected |
◆ Result()
int32_t choreographer::ChoreographerNodelet::Result |
( |
int32_t |
response | ) |
|
|
inlineprotected |
◆ SetInertiaCallback()
bool choreographer::ChoreographerNodelet::SetInertiaCallback |
( |
ff_msgs::SetInertia::Request & |
req, |
|
|
ff_msgs::SetInertia::Response & |
res |
|
) |
| |
|
inlineprotected |
◆ SetStateCallback()
bool choreographer::ChoreographerNodelet::SetStateCallback |
( |
ff_msgs::SetState::Request & |
req, |
|
|
ff_msgs::SetState::Response & |
res |
|
) |
| |
|
inlineprotected |
◆ UpdateCallback()
void choreographer::ChoreographerNodelet::UpdateCallback |
( |
FSM::State const & |
state, |
|
|
FSM::Event const & |
event |
|
) |
| |
|
inlineprotected |
◆ ValidateResult()
int32_t choreographer::ChoreographerNodelet::ValidateResult |
( |
int |
validator_response | ) |
|
|
inlineprotected |
The documentation for this class was generated from the following file: