test
pick_place_test.cpp
Go to the documentation of this file.
1
#include <
moveit/task_constructor/task.h
>
2
3
#include <
moveit/task_constructor/stages/current_state.h
>
4
#include <
moveit/task_constructor/stages/generate_grasp_pose.h
>
5
#include <
moveit/task_constructor/stages/simple_grasp.h
>
6
#include <
moveit/task_constructor/stages/pick.h
>
7
#include <
moveit/task_constructor/stages/connect.h
>
8
#include <
moveit/task_constructor/solvers/pipeline_planner.h
>
9
10
#include <
ros/ros.h
>
11
12
#include <
moveit_task_constructor_demo/pick_place_task.h
>
13
14
#include <gtest/gtest.h>
15
16
using namespace
moveit::task_constructor
;
17
18
TEST
(PickPlaceDemo, run) {
19
ros::NodeHandle
nh, pnh(
"~"
);
20
21
moveit_task_constructor_demo::setupDemoScene
(pnh);
22
23
// Construct and run pick/place task
24
moveit_task_constructor_demo::PickPlaceTask
pick_place_task(
"pick_place_task"
, pnh);
25
26
ASSERT_TRUE(pick_place_task.
init
());
27
28
ASSERT_TRUE(pick_place_task.
plan
());
29
ASSERT_TRUE(pick_place_task.
execute
());
30
}
31
32
int
main
(
int
argc,
char
** argv) {
33
testing::InitGoogleTest(&argc, argv);
34
ros::init
(argc, argv,
"pick_place_test"
);
35
ros::AsyncSpinner
spinner
(1);
36
spinner
.start();
37
38
return
RUN_ALL_TESTS();
39
}
pipeline_planner.h
pick.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
moveit_task_constructor_demo::PickPlaceTask::init
bool init()
Definition:
pick_place_task.cpp:178
ros.h
connect.h
ros::AsyncSpinner
TEST
TEST(PickPlaceDemo, run)
Definition:
pick_place_test.cpp:18
main
int main(int argc, char **argv)
Definition:
pick_place_test.cpp:32
simple_grasp.h
generate_grasp_pose.h
spinner
void spinner()
moveit_task_constructor_demo::PickPlaceTask::execute
bool execute()
Definition:
pick_place_task.cpp:538
current_state.h
moveit::task_constructor
task.h
moveit_task_constructor_demo::PickPlaceTask
Definition:
pick_place_task.h:99
moveit_task_constructor_demo::PickPlaceTask::plan
bool plan()
Definition:
pick_place_task.cpp:531
moveit_task_constructor_demo::setupDemoScene
void setupDemoScene(ros::NodeHandle &pnh)
Definition:
pick_place_task.cpp:124
pick_place_task.h
ros::NodeHandle
demo
Author(s): Robert Haschke
, Simon Goldstein
, Henning Kayser
autogenerated on Sat May 3 2025 02:40:30