|
ASCO Aerial Autonomy
|
#include <aerial_autonomy/actions_guards/base_functors.h>#include <aerial_autonomy/actions_guards/hovering_functors.h>#include <aerial_autonomy/actions_guards/manual_control_functors.h>#include <aerial_autonomy/actions_guards/shorting_action_sequence.h>#include <aerial_autonomy/logic_states/base_state.h>#include <aerial_autonomy/robot_systems/uav_arm_system.h>#include <aerial_autonomy/types/completed_event.h>#include <glog/logging.h>#include <thread>

Go to the source code of this file.
Classes | |
| struct | PickGuard_< LogicStateMachineT > |
| Logic to grab an object, sleep for few seconds Abort UAV, Arm controllers. More... | |
| struct | PickTransitionGuardFunctor_< LogicStateMachineT > |
| Check tracking is valid before starting visual servoing and arm is enabled before picking objects. More... | |
| struct | VisualServoingArmTransitionActionFunctor_< LogicStateMachineT, TransformIndex > |
| Set arm goal and set grip to false to start with. More... | |
| class | PrePickState_< LogicStateMachineT > |
| State that uses position control functor to reach a desired goal prior to picking. More... | |
Typedefs | |
| template<class LogicStateMachineT > | |
| using | PickInternalActionFunctor_ = boost::msm::front::ShortingActionSequence_< boost::mpl::vector< UAVStatusInternalActionFunctor_< LogicStateMachineT >, ArmStatusInternalActionFunctor_< LogicStateMachineT >, ControllerStatusInternalActionFunctor_< LogicStateMachineT, VisualServoingControllerArmConnector >, ControllerStatusInternalActionFunctor_< LogicStateMachineT, VisualServoingControllerDroneConnector, false >>> |
| Logic to check while reaching a visual servoing goal. More... | |
| template<class LogicStateMachineT > | |
| using | ManualControlArmInternalActionFunctor_ = boost::msm::front::ShortingActionSequence_< boost::mpl::vector< ArmStatusInternalActionFunctor_< LogicStateMachineT >, ManualControlInternalActionFunctor_< LogicStateMachineT >>> |
| Logic to check arm power and manual mode. More... | |
| template<class LogicStateMachineT > | |
| using | PickState_ = BaseState< UAVArmSystem, LogicStateMachineT, PickInternalActionFunctor_< LogicStateMachineT >> |
| State that uses position control functor to reach a desired goal. More... | |
| using ManualControlArmInternalActionFunctor_ = boost::msm::front::ShortingActionSequence_<boost::mpl::vector< ArmStatusInternalActionFunctor_<LogicStateMachineT>, ManualControlInternalActionFunctor_<LogicStateMachineT>>> |
Logic to check arm power and manual mode.
| LogicStateMachineT | Logic state machine used to process events |
| using PickInternalActionFunctor_ = boost::msm::front::ShortingActionSequence_<boost::mpl::vector< UAVStatusInternalActionFunctor_<LogicStateMachineT>, ArmStatusInternalActionFunctor_<LogicStateMachineT>, ControllerStatusInternalActionFunctor_< LogicStateMachineT, VisualServoingControllerArmConnector>, ControllerStatusInternalActionFunctor_< LogicStateMachineT, VisualServoingControllerDroneConnector, false>>> |
Logic to check while reaching a visual servoing goal.
| LogicStateMachineT | Logic state machine used to process events |
| using PickState_ = BaseState<UAVArmSystem, LogicStateMachineT, PickInternalActionFunctor_<LogicStateMachineT>> |
State that uses position control functor to reach a desired goal.
| LogicStateMachineT | Logic state machine used to process events |
1.8.6