Skip to content

Commit 9705a55

Browse files
committed
Avoid segfault and improve error warnings
1 parent 3b41a22 commit 9705a55

File tree

3 files changed

+27
-21
lines changed

3 files changed

+27
-21
lines changed

capabilities/src/execute_task_solution_capability.cpp

+2-4
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@
4646
#include <fmt/format.h>
4747

4848
namespace {
49-
49+
const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_task_constructor_visualization.execute_task_solution");
5050
// TODO: move to moveit::core::RobotModel
5151
const moveit::core::JointModelGroup* findJointModelGroup(const moveit::core::RobotModel& model,
5252
const std::vector<std::string>& joints) {
@@ -73,13 +73,11 @@ const moveit::core::JointModelGroup* findJointModelGroup(const moveit::core::Rob
7373
return jmg;
7474
}
7575
}
76-
76+
RCLCPP_WARN(LOGGER, "Could not find JointModelGroup that actuates {}", fmt::join(joints, ", "));
7777
return nullptr;
7878
}
7979
} // namespace
8080

81-
static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_task_constructor_visualization.execute_task_solution");
82-
8381
namespace move_group {
8482

8583
ExecuteTaskSolutionCapability::ExecuteTaskSolutionCapability() : MoveGroupCapability("ExecuteTaskSolution") {}

core/src/container.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -345,6 +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));
348349
return nullptr;
349350
}
350351

core/src/stages/compute_ik.cpp

+24-17
Original file line numberDiff line numberDiff line change
@@ -314,6 +314,11 @@ void ComputeIK::compute() {
314314

315315
link = scene->getCurrentState().getRigidlyConnectedParentLinkModel(ik_pose_msg.header.frame_id);
316316

317+
if (!link) {
318+
RCLCPP_WARN_STREAM(
319+
LOGGER, fmt::format("ik frame '{}' is not rigidly connected to any link", ik_pose_msg.header.frame_id));
320+
return;
321+
}
317322
// transform target pose such that ik frame will reach there if link does
318323
target_pose = target_pose * ik_pose.inverse() * scene->getCurrentState().getFrameTransform(link->getName());
319324
}
@@ -336,23 +341,25 @@ void ComputeIK::compute() {
336341
marker.color.a *= 0.5;
337342
eef_markers.push_back(marker);
338343
};
339-
const auto& links_to_visualize = moveit::core::RobotModel::getRigidlyConnectedParentLinkModel(link)
340-
->getParentJointModel()
341-
->getDescendantLinkModels();
342-
if (colliding) {
343-
SubTrajectory solution;
344-
std::copy(frame_markers.begin(), frame_markers.end(), std::back_inserter(solution.markers()));
345-
generateCollisionMarkers(sandbox_state, appender, links_to_visualize);
346-
std::copy(eef_markers.begin(), eef_markers.end(), std::back_inserter(solution.markers()));
347-
solution.markAsFailure();
348-
// TODO: visualize collisions
349-
solution.setComment(s.comment() + " eef in collision: " + listCollisionPairs(collisions.contacts, ", "));
350-
auto colliding_scene{ scene->diff() };
351-
colliding_scene->setCurrentState(sandbox_state);
352-
spawn(InterfaceState(colliding_scene), std::move(solution));
353-
return;
354-
} else
355-
generateVisualMarkers(sandbox_state, appender, links_to_visualize);
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+
}
356363

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

0 commit comments

Comments
 (0)