Skip to content

Fix seg fault with attached objects during motion execution #3466

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 6 commits into from
May 12, 2025
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 4 additions & 2 deletions moveit_core/robot_state/src/robot_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1217,14 +1217,16 @@ void RobotState::getAttachedBodies(std::vector<const AttachedBody*>& attached_bo
attached_bodies.clear();
attached_bodies.reserve(attached_body_map_.size());
for (const auto& it : attached_body_map_)
attached_bodies.push_back(it.second.get());
if (it.second)
attached_bodies.push_back(it.second.get());
}

void RobotState::getAttachedBodies(std::map<std::string, const AttachedBody*>& attached_bodies) const
{
attached_bodies.clear();
for (const auto& it : attached_body_map_)
attached_bodies[it.first] = it.second.get();
if (it.second && !it.first.empty())
attached_bodies[it.first] = it.second.get();
}

void RobotState::getAttachedBodies(std::vector<const AttachedBody*>& attached_bodies, const JointModelGroup* group) const
Expand Down
8 changes: 5 additions & 3 deletions moveit_ros/planning/plan_execution/src/plan_execution.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -286,7 +286,8 @@ bool plan_execution::PlanExecution::isRemainingPathValid(const ExecutableMotionP
moveit::core::RobotState state = plan.planning_scene->getCurrentState();
std::map<std::string, const moveit::core::AttachedBody*> current_attached_objects, waypoint_attached_objects;
state.getAttachedBodies(current_attached_objects);
waypoint_attached_objects = plan_components_attached_objects_[path_segment.first];
if (plan_components_attached_objects_.size() > static_cast<size_t>(path_segment.first))
waypoint_attached_objects = plan_components_attached_objects_[path_segment.first];
for (std::size_t i = std::max(path_segment.second - 1, 0); i < wpc; ++i)
{
collision_detection::CollisionResult res;
Expand Down Expand Up @@ -469,7 +470,7 @@ moveit_msgs::msg::MoveItErrorCodes plan_execution::PlanExecution::executeAndMoni
{
const auto& trajectory = component.trajectory;
std::map<std::string, const moveit::core::AttachedBody*> trajectory_attached_objects;
if (trajectory)
if (trajectory && trajectory->getWayPointCount() > 0)
{
std::map<std::string, const moveit::core::AttachedBody*> attached_objects;
trajectory->getWayPoint(0).getAttachedBodies(trajectory_attached_objects);
Expand All @@ -483,7 +484,8 @@ moveit_msgs::msg::MoveItErrorCodes plan_execution::PlanExecution::executeAndMoni
}
}
}
plan_components_attached_objects_.push_back(trajectory_attached_objects);
if (trajectory_attached_objects.size() > 0)
plan_components_attached_objects_.push_back(trajectory_attached_objects);
}

while (rclcpp::ok() && !execution_complete_ && !path_became_invalid_)
Expand Down
Loading