#include <chrono>
#include <condition_variable>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <iostream>
#include <memory>
#include <mutex>
#include <stdexcept>
#include <thread>
#include <actionlib/client/simple_action_client.h>
#include <moveit/move_group_interface/move_group_interface.h>
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_model_loader/robot_model_loader.h>
#include <moveit/robot_state/conversions.h>
#include <moveit_msgs/Constraints.h>
#include <moveit_msgs/GetMotionPlan.h>
#include <moveit_msgs/JointConstraint.h>
#include <ros/ros.h>
#include <sensor_msgs/JointState.h>
#include <pilz_industrial_motion_planner_testutils/async_test.h>
#include <pilz_industrial_motion_planner_testutils/checks.h>
#include <pilz_industrial_motion_planner_testutils/sequence.h>
#include <pilz_industrial_motion_planner_testutils/xml_testdata_loader.h>
#include <moveit_msgs/MoveGroupSequenceAction.h>
Go to the source code of this file.
◆ GROUP_NAME()
const std::string GROUP_NAME |
( |
"group_name" |
| ) |
|
◆ JOINT_POSITION_TOLERANCE()
const std::string JOINT_POSITION_TOLERANCE |
( |
"joint_position_tolerance" |
| ) |
|
◆ main()
int main |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
◆ SEQUENCE_ACTION_NAME()
const std::string SEQUENCE_ACTION_NAME |
( |
"/sequence_move_group" |
| ) |
|
◆ TEST_DATA_FILE_NAME()
const std::string TEST_DATA_FILE_NAME |
( |
"testdata_file_name" |
| ) |
|
◆ TEST_F()
Tests that goal can be cancelled.
Test Sequence:
- Send goal for planning and execution.
- Cancel goal before it finishes.
Expected Results:
- Goal is sent to the action server.
- Goal is cancelled. Execution stops.
Definition at line 151 of file integrationtest_sequence_action_preemption.cpp.
◆ GOAL_SUCCEEDED_EVENT
const std::string GOAL_SUCCEEDED_EVENT = "GOAL_SUCCEEDED" |
◆ SERVER_IDLE_EVENT
const std::string SERVER_IDLE_EVENT = "SERVER_IDLE" |