| 
|   | MOCK_METHOD0 (active_callback, void()) | 
|   | 
|   | MOCK_METHOD1 (feedback_callback, void(const moveit_msgs::msg::MoveGroupSequenceFeedbackConstPtr &feedback)) | 
|   | 
|   | MOCK_METHOD2 (done_callback, void(const actionlib::SimpleClientGoalState &state, const moveit_msgs::msg::MoveGroupSequenceResultConstPtr &result)) | 
|   | 
|   | MOCK_METHOD0 (active_callback, void()) | 
|   | 
|   | MOCK_METHOD1 (feedback_callback, void(const moveit_msgs::msg::MoveGroupSequenceFeedbackConstPtr &feedback)) | 
|   | 
|   | MOCK_METHOD2 (done_callback, void(const actionlib::SimpleClientGoalState &state, const moveit_msgs::msg::MoveGroupSequenceResultConstPtr &result)) | 
|   | 
| void  | triggerClearEvent (const std::string &event) | 
|   | Triggers a clear event. If a call to barricade is currently pending it will unblock as soon as all clear events are triggered. Else the event is put on the waitlist. This waitlist is emptied upon a call to barricade.  More...
  | 
|   | 
| bool  | barricade (const std::string &clear_event, const int timeout_ms=-1) | 
|   | Will block until the event given by clear_event is triggered or a timeout is reached. Unblocks immediately, if the event was on the waitlist.  More...
  | 
|   | 
| bool  | barricade (std::initializer_list< std::string > clear_events, const int timeout_ms=-1) | 
|   | Will block until all events given by clear_events are triggered or a timeout is reached. Events on the waitlist are taken into account, too.  More...
  | 
|   | 
◆ MOCK_METHOD0() [1/2]
      
        
          | IntegrationTestSequenceAction::MOCK_METHOD0  | 
          ( | 
          active_callback  | 
          ,  | 
        
        
           | 
           | 
          void()  | 
            | 
        
        
           | 
          ) | 
           |  | 
        
      
 
 
◆ MOCK_METHOD0() [2/2]
      
        
          | IntegrationTestSequenceAction::MOCK_METHOD0  | 
          ( | 
          active_callback  | 
          ,  | 
        
        
           | 
           | 
          void()  | 
            | 
        
        
           | 
          ) | 
           |  | 
        
      
 
 
◆ MOCK_METHOD1() [1/2]
      
        
          | IntegrationTestSequenceAction::MOCK_METHOD1  | 
          ( | 
          feedback_callback  | 
          ,  | 
        
        
           | 
           | 
          void(const moveit_msgs::msg::MoveGroupSequenceFeedbackConstPtr &feedback)  | 
            | 
        
        
           | 
          ) | 
           |  | 
        
      
 
 
◆ MOCK_METHOD1() [2/2]
      
        
          | IntegrationTestSequenceAction::MOCK_METHOD1  | 
          ( | 
          feedback_callback  | 
          ,  | 
        
        
           | 
           | 
          void(const moveit_msgs::msg::MoveGroupSequenceFeedbackConstPtr &feedback)  | 
            | 
        
        
           | 
          ) | 
           |  | 
        
      
 
 
◆ MOCK_METHOD2() [1/2]
      
        
          | IntegrationTestSequenceAction::MOCK_METHOD2  | 
          ( | 
          done_callback  | 
          ,  | 
        
        
           | 
           | 
          void(const actionlib::SimpleClientGoalState &state, const moveit_msgs::msg::MoveGroupSequenceResultConstPtr &result)  | 
            | 
        
        
           | 
          ) | 
           |  | 
        
      
 
 
◆ MOCK_METHOD2() [2/2]
      
        
          | IntegrationTestSequenceAction::MOCK_METHOD2  | 
          ( | 
          done_callback  | 
          ,  | 
        
        
           | 
           | 
          void(const actionlib::SimpleClientGoalState &state, const moveit_msgs::msg::MoveGroupSequenceResultConstPtr &result)  | 
            | 
        
        
           | 
          ) | 
           |  | 
        
      
 
 
◆ SetUp() [1/2]
  
  
      
        
          | void IntegrationTestSequenceAction::SetUp  | 
          ( | 
           | ) | 
           | 
         
       
   | 
  
overrideprotected   | 
  
 
 
◆ SetUp() [2/2]
  
  
      
        
          | void IntegrationTestSequenceAction::SetUp  | 
          ( | 
           | ) | 
           | 
         
       
   | 
  
overrideprotected   | 
  
 
 
◆ ac_
  
  
      
        
          | actionlib::SimpleActionClient< moveit_msgs::msg::MoveGroupSequenceAction > IntegrationTestSequenceAction::ac_ { ph_, SEQUENCE_ACTION_NAME, true } | 
         
       
   | 
  
protected   | 
  
 
 
◆ data_loader_
◆ group_name_
  
  
      
        
          | std::string IntegrationTestSequenceAction::group_name_ | 
         
       
   | 
  
protected   | 
  
 
 
◆ joint_position_tolerance_
  
  
      
        
          | double IntegrationTestSequenceAction::joint_position_tolerance_ | 
         
       
   | 
  
protected   | 
  
 
 
◆ model_loader_
◆ move_group_
◆ ph_
  
  
      
        
          | ros::NodeHandle IntegrationTestSequenceAction::ph_ { "~" } | 
         
       
   | 
  
protected   | 
  
 
 
◆ robot_model_
  
  
      
        
          | robot_model::RobotModelPtr IntegrationTestSequenceAction::robot_model_ | 
         
       
   | 
  
protected   | 
  
 
 
◆ start_config
◆ test_data_file_name_
  
  
      
        
          | std::string IntegrationTestSequenceAction::test_data_file_name_ | 
         
       
   | 
  
protected   | 
  
 
 
The documentation for this class was generated from the following files: