mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
Add return value to Task::execute (#136)
This commit is contained in:
parent
c44d0cac19
commit
534d520a04
@ -46,6 +46,8 @@
|
||||
|
||||
#include <moveit/macros/class_forward.h>
|
||||
|
||||
#include <moveit_msgs/MoveItErrorCodes.h>
|
||||
|
||||
namespace moveit {
|
||||
namespace core {
|
||||
MOVEIT_CLASS_FORWARD(RobotModel)
|
||||
@ -119,8 +121,8 @@ public:
|
||||
bool plan(size_t max_solutions = 0);
|
||||
/// interrupt current planning (or execution)
|
||||
void preempt();
|
||||
/// execute solution
|
||||
void execute(const SolutionBase& s);
|
||||
/// execute solution, return the result
|
||||
moveit_msgs::MoveItErrorCodes execute(const SolutionBase& s);
|
||||
|
||||
/// print current task state (number of found solutions and propagated states) to std::cout
|
||||
void printState(std::ostream& os = std::cout) const;
|
||||
|
||||
@ -303,7 +303,7 @@ void Task::preempt() {
|
||||
pimpl()->preempt_requested_ = true;
|
||||
}
|
||||
|
||||
void Task::execute(const SolutionBase& s) {
|
||||
moveit_msgs::MoveItErrorCodes Task::execute(const SolutionBase& s) {
|
||||
actionlib::SimpleActionClient<moveit_task_constructor_msgs::ExecuteTaskSolutionAction> ac("execute_task_solution");
|
||||
ac.waitForServer();
|
||||
|
||||
@ -311,6 +311,7 @@ void Task::execute(const SolutionBase& s) {
|
||||
s.fillMessage(goal.solution, pimpl()->introspection_.get());
|
||||
ac.sendGoal(goal);
|
||||
ac.waitForResult();
|
||||
return ac.getResult()->error_code;
|
||||
}
|
||||
|
||||
void Task::publishAllSolutions(bool wait) {
|
||||
|
||||
Loading…
Reference in New Issue
Block a user