Skip to content

Commit

Permalink
Fix segfault with uninitialized JogArm thread (moveit#1882)
Browse files Browse the repository at this point in the history
  • Loading branch information
henningkayser authored and tylerjw committed May 12, 2020
1 parent cdc76f7 commit f6f8acc
Showing 1 changed file with 6 additions and 12 deletions.
18 changes: 6 additions & 12 deletions moveit_experimental/moveit_jog_arm/src/jog_cpp_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,19 +214,13 @@ sensor_msgs::JointState JogCppApi::getJointState()

bool JogCppApi::getCommandFrameTransform(Eigen::Isometry3d& transform)
{
if (jog_calcs_->isInitialized())
{
shared_variables_mutex_.lock();
transform = shared_variables_.tf_moveit_to_cmd_frame;
shared_variables_mutex_.unlock();

// All zeros means the transform wasn't initialized, so return false
if (transform.matrix().isZero(0))
return false;
}
else
if (!jog_calcs_ || !jog_calcs_->isInitialized())
return false;

return true;
const std::lock_guard<std::mutex> lock(shared_variables_mutex_);
transform = shared_variables_.tf_moveit_to_cmd_frame;

// All zeros means the transform wasn't initialized, so return false
return !transform.matrix().isZero(0);
}
} // namespace moveit_jog_arm

0 comments on commit f6f8acc

Please sign in to comment.