MTC
introspection.h
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Bielefeld University
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Bielefeld University nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Robert Haschke
36  Desc: Introspection provides ROS interfaces to introspect Task instances
37 */
38 
39 #pragma once
40 
41 #include <moveit/macros/class_forward.h>
42 #include <moveit_task_constructor_msgs/TaskDescription.h>
43 #include <moveit_task_constructor_msgs/TaskStatistics.h>
44 #include <moveit_task_constructor_msgs/Solution.h>
45 #include <moveit_task_constructor_msgs/GetSolution.h>
46 
47 #define DESCRIPTION_TOPIC "description"
48 #define STATISTICS_TOPIC "statistics"
49 #define SOLUTION_TOPIC "solution"
50 #define GET_SOLUTION_SERVICE "get_solution"
51 
52 namespace moveit {
53 namespace task_constructor {
54 
55 MOVEIT_CLASS_FORWARD(Stage);
56 MOVEIT_CLASS_FORWARD(SolutionBase);
57 
58 class TaskPrivate;
59 class IntrospectionPrivate;
60 
66 {
67  IntrospectionPrivate* impl;
68 
69 public:
70  Introspection(const TaskPrivate* task);
71  Introspection(const Introspection& other) = delete;
72  ~Introspection();
73 
75  moveit_task_constructor_msgs::TaskDescription&
76  fillTaskDescription(moveit_task_constructor_msgs::TaskDescription& msg);
79 
81  moveit_task_constructor_msgs::TaskStatistics& fillTaskStatistics(moveit_task_constructor_msgs::TaskStatistics& msg);
83  void publishTaskState();
84 
86  void reset();
87 
89  void registerSolution(const SolutionBase& s);
90 
92  void publishSolution(const SolutionBase& s);
93 
95  void publishAllSolutions(bool wait = true);
96 
98  bool getSolution(moveit_task_constructor_msgs::GetSolution::Request& req,
99  moveit_task_constructor_msgs::GetSolution::Response& res);
100 
102  uint32_t stageId(const moveit::task_constructor::Stage* const s) const;
103 
106 
107 private:
108  void fillStageStatistics(const Stage& stage, moveit_task_constructor_msgs::StageStatistics& s);
109  void fillSolution(moveit_task_constructor_msgs::Solution& msg, const SolutionBase& s);
111  uint32_t stageId(const moveit::task_constructor::Stage* const s);
113  const SolutionBase* solutionFromId(uint id) const;
114 };
115 } // namespace task_constructor
116 } // namespace moveit
Definition: introspection.h:66
moveit_task_constructor_msgs::TaskDescription & fillTaskDescription(moveit_task_constructor_msgs::TaskDescription &msg)
fill task description message for publishing the task configuration
Definition: introspection.cpp:231
void publishSolution(const SolutionBase &s)
publish the given solution
Definition: introspection.cpp:163
void publishTaskDescription()
publish detailed task description
Definition: introspection.cpp:139
bool getSolution(moveit_task_constructor_msgs::GetSolution::Request &req, moveit_task_constructor_msgs::GetSolution::Response &res)
get solution
Definition: introspection.cpp:189
moveit_task_constructor_msgs::TaskStatistics & fillTaskStatistics(moveit_task_constructor_msgs::TaskStatistics &msg)
fill task state message for publishing the current task state
Definition: introspection.cpp:266
void registerSolution(const SolutionBase &s)
register the given solution, assigning a unique ID
Definition: introspection.cpp:154
void publishAllSolutions(bool wait=true)
publish all top-level solutions of task
Definition: introspection.cpp:169
void reset()
indicate that this task was reset
Definition: introspection.cpp:149
uint32_t stageId(const moveit::task_constructor::Stage *const s) const
retrieve id of given stage
Definition: introspection.cpp:202
uint32_t solutionId(const moveit::task_constructor::SolutionBase &s)
retrieve or set id of given solution
Definition: introspection.cpp:209
void publishTaskState()
publish the current state of task
Definition: introspection.cpp:144
abstract base class for solutions (primitive and sequences)
Definition: storage.h:269
Definition: stage.h:147