fixup! Reset joint values in scene diff for execution (#504)

This commit is contained in:
Robert Haschke 2023-11-09 11:28:02 +01:00 committed by GitHub
parent 06b7b77e9e
commit 2f06438a86
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
2 changed files with 3 additions and 7 deletions

View File

@ -237,6 +237,9 @@ void SubTrajectory::appendTo(moveit_task_constructor_msgs::msg::Solution& msg, I
trajectory()->getRobotTrajectoryMsg(t.trajectory);
this->end()->scene()->getPlanningSceneDiffMsg(t.scene_diff);
// reset JointStates (joints are already handled in trajectories)
t.scene_diff.robot_state.joint_state = sensor_msgs::msg::JointState();
t.scene_diff.robot_state.multi_dof_joint_state = sensor_msgs::msg::MultiDOFJointState();
}
double SubTrajectory::computeCost(const CostTerm& f, std::string& comment) const {

View File

@ -281,13 +281,6 @@ moveit::core::MoveItErrorCode Task::execute(const SolutionBase& s) {
moveit_task_constructor_msgs::action::ExecuteTaskSolution::Goal goal;
s.toMsg(goal.solution, pimpl()->introspection_.get());
// Reset joint values in scene diff to prevent any execution capability from
// modifying the planning scene joint values
for (auto& sub_trajectory : goal.solution.sub_trajectory) {
sub_trajectory.scene_diff.robot_state.joint_state = sensor_msgs::msg::JointState();
sub_trajectory.scene_diff.robot_state.multi_dof_joint_state = sensor_msgs::msg::MultiDOFJointState();
}
moveit_msgs::msg::MoveItErrorCodes error_code;
error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
auto goal_handle_future = ac->async_send_goal(goal);