moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
IntegrationTestSequenceAction Class Reference
Inheritance diagram for IntegrationTestSequenceAction:
Inheritance graph
[legend]
Collaboration diagram for IntegrationTestSequenceAction:
Collaboration graph
[legend]

Public Member Functions

 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))
 
- Public Member Functions inherited from testing::AsyncTest
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.
 
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.
 
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.
 

Protected Member Functions

void SetUp () override
 
void SetUp () override
 

Protected Attributes

ros::NodeHandle ph_ { "~" }
 
actionlib::SimpleActionClient< moveit_msgs::msg::MoveGroupSequenceAction > ac_ { ph_, SEQUENCE_ACTION_NAME, true }
 
std::shared_ptr< moveit::planning_interface::MoveGroupInterfacemove_group_
 
robot_model_loader::RobotModelLoader model_loader_
 
robot_model::RobotModelPtr robot_model_
 
double joint_position_tolerance_
 
std::string test_data_file_name_
 
std::string group_name_
 
TestdataLoaderUPtr data_loader_
 
JointConfiguration start_config
 The configuration at which the robot stays at the beginning of each test.
 
- Protected Attributes inherited from testing::AsyncTest
std::mutex m_
 
std::condition_variable cv_
 
std::set< std::string > clear_events_ {}
 
std::set< std::string > waitlist_ {}
 

Detailed Description

Definition at line 79 of file integrationtest_sequence_action.cpp.

Member Function Documentation

◆ 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

Definition at line 107 of file integrationtest_sequence_action.cpp.

Here is the call graph for this function:

◆ SetUp() [2/2]

void IntegrationTestSequenceAction::SetUp ( )
overrideprotected

Member Data Documentation

◆ ac_

actionlib::SimpleActionClient< moveit_msgs::msg::MoveGroupSequenceAction > IntegrationTestSequenceAction::ac_ { ph_, SEQUENCE_ACTION_NAME, true }
protected

Definition at line 92 of file integrationtest_sequence_action.cpp.

◆ data_loader_

TestdataLoaderUPtr IntegrationTestSequenceAction::data_loader_
protected

Definition at line 101 of file integrationtest_sequence_action.cpp.

◆ group_name_

std::string IntegrationTestSequenceAction::group_name_
protected

Definition at line 100 of file integrationtest_sequence_action.cpp.

◆ joint_position_tolerance_

double IntegrationTestSequenceAction::joint_position_tolerance_
protected

Definition at line 97 of file integrationtest_sequence_action.cpp.

◆ model_loader_

robot_model_loader::RobotModelLoader IntegrationTestSequenceAction::model_loader_
protected

Definition at line 95 of file integrationtest_sequence_action.cpp.

◆ move_group_

std::shared_ptr< moveit::planning_interface::MoveGroupInterface > IntegrationTestSequenceAction::move_group_
protected

Definition at line 93 of file integrationtest_sequence_action.cpp.

◆ ph_

ros::NodeHandle IntegrationTestSequenceAction::ph_ { "~" }
protected

Definition at line 91 of file integrationtest_sequence_action.cpp.

◆ robot_model_

robot_model::RobotModelPtr IntegrationTestSequenceAction::robot_model_
protected

Definition at line 96 of file integrationtest_sequence_action.cpp.

◆ start_config

JointConfiguration IntegrationTestSequenceAction::start_config
protected

The configuration at which the robot stays at the beginning of each test.

Definition at line 104 of file integrationtest_sequence_action.cpp.

◆ test_data_file_name_

std::string IntegrationTestSequenceAction::test_data_file_name_
protected

Definition at line 99 of file integrationtest_sequence_action.cpp.


The documentation for this class was generated from the following files: