Skip to content

Commit 677529a

Browse files
authored
Apply suggestions from code review
1 parent f529160 commit 677529a

File tree

3 files changed

+18
-21
lines changed

3 files changed

+18
-21
lines changed

capabilities/src/execute_task_solution_capability.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,6 @@ const moveit::core::JointModelGroup* findJointModelGroup(const moveit::core::Rob
7373
return jmg;
7474
}
7575
}
76-
RCLCPP_WARN(LOGGER, fmt::format("Could not find JointModelGroup that actuates {}", fmt::join(joints, ", ")));
7776
return nullptr;
7877
}
7978
} // namespace

core/src/container.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -345,7 +345,7 @@ Stage* ContainerBase::findChild(const std::string& name) const {
345345
else if (auto* parent = dynamic_cast<const ContainerBase*>(child.get()))
346346
return parent->findChild(name.substr(pos + 1));
347347
}
348-
RCLCPP_WARN_STREAM(rclcpp::get_logger("ContainerBase"), fmt::format("Child '{}' not found", name));
348+
RCLCPP_DEBUG_STREAM(rclcpp::get_logger("ContainerBase"), fmt::format("Child '{}' not found", name));
349349
return nullptr;
350350
}
351351

core/src/stages/compute_ik.cpp

+17-19
Original file line numberDiff line numberDiff line change
@@ -341,25 +341,23 @@ void ComputeIK::compute() {
341341
marker.color.a *= 0.5;
342342
eef_markers.push_back(marker);
343343
};
344-
auto const& connected_parent_link_model = moveit::core::RobotModel::getRigidlyConnectedParentLinkModel(link);
345-
if (connected_parent_link_model && connected_parent_link_model->getParentJointModel()) {
346-
const auto& links_to_visualize = connected_parent_link_model->getParentJointModel()->getDescendantLinkModels();
347-
if (colliding) {
348-
SubTrajectory solution;
349-
std::copy(frame_markers.begin(), frame_markers.end(), std::back_inserter(solution.markers()));
350-
generateCollisionMarkers(sandbox_state, appender, links_to_visualize);
351-
std::copy(eef_markers.begin(), eef_markers.end(), std::back_inserter(solution.markers()));
352-
solution.markAsFailure();
353-
// TODO: visualize collisions
354-
solution.setComment(s.comment() + " eef in collision: " + listCollisionPairs(collisions.contacts, ", "));
355-
auto colliding_scene{ scene->diff() };
356-
colliding_scene->setCurrentState(sandbox_state);
357-
spawn(InterfaceState(colliding_scene), std::move(solution));
358-
return;
359-
} else {
360-
generateVisualMarkers(sandbox_state, appender, links_to_visualize);
361-
}
362-
}
344+
const auto& links_to_visualize = moveit::core::RobotModel::getRigidlyConnectedParentLinkModel(link)
345+
->getParentJointModel()
346+
->getDescendantLinkModels();
347+
if (colliding) {
348+
SubTrajectory solution;
349+
std::copy(frame_markers.begin(), frame_markers.end(), std::back_inserter(solution.markers()));
350+
generateCollisionMarkers(sandbox_state, appender, links_to_visualize);
351+
std::copy(eef_markers.begin(), eef_markers.end(), std::back_inserter(solution.markers()));
352+
solution.markAsFailure();
353+
// TODO: visualize collisions
354+
solution.setComment(s.comment() + " eef in collision: " + listCollisionPairs(collisions.contacts, ", "));
355+
auto colliding_scene{ scene->diff() };
356+
colliding_scene->setCurrentState(sandbox_state);
357+
spawn(InterfaceState(colliding_scene), std::move(solution));
358+
return;
359+
} else
360+
generateVisualMarkers(sandbox_state, appender, links_to_visualize);
363361

364362
// determine joint values of robot pose to compare IK solution with for costs
365363
std::vector<double> compare_pose;

0 commit comments

Comments
 (0)