modified ExecuteTaskSolution.action

This commit is contained in:
Robert Haschke 2018-06-10 18:29:52 +02:00
parent 387fa5c087
commit 99a7a9bc9a
2 changed files with 7 additions and 5 deletions

View File

@ -103,7 +103,7 @@ void ExecuteTaskSolutionCapability::goalCallback(const moveit_task_constructor_m
}
plan_execution::ExecutableMotionPlan plan;
if(!constructMotionPlan(goal->task_solution, plan))
if(!constructMotionPlan(goal->solution, plan))
result.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN;
else {
ROS_INFO_NAMED("ExecuteTaskSolution", "Executing TaskSolution");
@ -125,7 +125,8 @@ void ExecuteTaskSolutionCapability::preemptCallback() {
context_->plan_execution_->stop();
}
bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constructor_msgs::Solution& solution, plan_execution::ExecutableMotionPlan& plan) {
bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constructor_msgs::Solution& solution,
plan_execution::ExecutableMotionPlan& plan) {
robot_model::RobotModelConstPtr model = context_->planning_scene_monitor_->getRobotModel();
robot_state::RobotState state(model);

View File

@ -1,5 +1,5 @@
# Task solution to execute
Solution task_solution
Solution solution
---
@ -8,5 +8,6 @@ moveit_msgs/MoveItErrorCodes error_code
---
# current stage/subtrajectory during execution
string state
# finished subtrajectory id / number
uint32 sub_id
uint32 sub_no