#include <boost/statechart/event.hpp>#include <boost/statechart/state_machine.hpp>#include <boost/statechart/simple_state.hpp>#include <boost/statechart/state.hpp>#include <boost/statechart/transition.hpp>#include <boost/statechart/in_state_reaction.hpp>#include <boost/statechart/custom_reaction.hpp>#include <boost/mpl/list.hpp>#include <boost/shared_ptr.hpp>#include <boost/function.hpp>#include <iostream>#include <iomanip>#include <algorithm>#include "nasa_common_logging/Logger.h"#include <r2_msgs/JointControlData.h>#include <sensor_msgs/JointState.h>#include <actionlib_msgs/GoalStatusArray.h>#include <r2_msgs/JointCommand.h>#include <boost/regex.hpp>#include "robodyn_mechanisms/GripperKinematics.h"#include "robodyn_utilities/AbsSlewFilter.h"#include "robot_instance/GripperSetpointFactory.h"#include "fsm_utils/StatechartUtilities.h"

Go to the source code of this file.
Classes | |
| struct | Acting |
| Done is the initial internal transition only as a default because there has to be something, and it seems like the one to cause the least problems. More... | |
| struct | Active |
| has to be a boost::statechart::state because of the context<> in the constructor More... | |
| struct | AtDesiredJawPosition |
| struct | c_cancel |
| struct | c_lock |
| struct | c_release |
| struct | c_set |
| struct | c_setParameters |
| struct | Close |
| has to be a boost::statechart::state because of the post_event in the constructor More... | |
| struct | Closing |
| struct | Container |
| struct | Done |
| has to be a boost::statechart::state because of the post_event in the constructor More... | |
| struct | e_atDesiredJawPosition |
| struct | e_close |
| struct | e_do |
| EELockedInitValue. More... | |
| struct | e_done |
| struct | e_faulted |
| struct | e_isClosed |
| struct | e_isNotOpen |
| struct | e_isOpen |
| struct | e_lessThanDesiredJawPosition |
| struct | e_lessThanForceThreshold |
| struct | e_listen |
| struct | e_loaded |
| struct | e_lock |
| struct | e_locked |
| struct | e_lockedStatus |
| struct | e_moreThanDesiredJawPosition |
| struct | e_moreThanForceThreshold |
| struct | e_moving |
| struct | e_next |
| struct | e_notFaulted |
| struct | e_notStalled |
| struct | e_open |
| struct | e_ready |
| struct | e_release |
| struct | e_set |
| struct | e_stalled |
| struct | e_still |
| struct | e_stop |
| struct | e_unloaded |
| struct | e_unlocked |
| struct | e_unlockedStatus |
| struct | e_unready |
| struct | Faulted |
| struct | GripperPosition |
| State Machine Definition. More... | |
| struct | i_atDesiredJawPosition_action |
| struct | i_atDesiredJawPosition_position |
| struct | i_do_active |
| struct | i_do_fault |
| struct | i_do_force |
| struct | i_do_load |
| struct | i_do_lock |
| struct | i_do_lockStatus |
| struct | i_do_movement |
| struct | i_do_moving |
| struct | i_do_open |
| struct | i_do_position |
| struct | i_do_positionOrLess |
| struct | i_do_stall |
| struct | i_do_status |
| struct | i_faulted_command |
| struct | i_faulted_fault |
| struct | i_isOpen_action |
| struct | i_isOpen_movement |
| struct | i_isOpen_open |
| struct | i_locked_action |
| struct | i_locked_lock |
| struct | i_ready_command |
| struct | i_ready_status |
| struct | i_stalled_action |
| struct | i_stalled_stall |
| struct | i_still_action |
| struct | i_still_moving |
| struct | i_unready_command |
| struct | i_unready_status |
| struct | Inactive |
| has to be a boost::statechart::state because of the context<> in the constructor More... | |
| struct | JawPositionCheck |
| has to be a boost::statechart::state because of the post_event in the constructor More... | |
| struct | LessThanDesiredJawPosition |
| struct | LessThanForceThreshold |
| struct | Listening |
| has to be a boost::statechart::state because of the post_event in the constructor More... | |
| struct | Loaded |
| struct | LockCheck |
| has to be a boost::statechart::state because of the post_event in the constructor More... | |
| struct | Locked |
| struct | LockedStatus |
| struct | MoreThanDesiredJawPosition |
| struct | MoreThanForceThreshold |
| struct | Moving |
| struct | NotFaulted |
| struct | NotOpen |
| struct | NotStalled |
| struct | Open |
| struct | Opening |
| struct | OpenUntilStall |
| has to be a boost::statechart::state because of the post_event in the constructor More... | |
| struct | OpenWide |
| has to be a boost::statechart::state because of the post_event in the constructor More... | |
| struct | Ready |
| struct | Stalled |
| struct | Still |
| struct | Stopped |
| has to be a boost::statechart::state because of the context<> in the constructor More... | |
| struct | Unloaded |
| struct | Unlocked |
| struct | UnlockedStatus |
| struct | Unready |