Skip to content
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

Make GILReleaser exception-safe #2363

Merged
merged 1 commit into from
Oct 13, 2020
Merged
Show file tree
Hide file tree
Changes from all 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
Original file line number Diff line number Diff line change
Expand Up @@ -458,10 +458,12 @@ class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer

bp::tuple planPython()
{
GILReleaser gr;
MoveGroupInterface::Plan plan;
moveit_msgs::MoveItErrorCodes res = MoveGroupInterface::plan(plan);
gr.reacquire();
moveit_msgs::MoveItErrorCodes res;
{
GILReleaser gr;
res = MoveGroupInterface::plan(plan);
}
return bp::make_tuple(py_bindings_tools::serializeMsg(res), py_bindings_tools::serializeMsg(plan.trajectory_),
plan.planning_time_);
}
Expand All @@ -488,10 +490,11 @@ class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer
std::vector<geometry_msgs::Pose> poses;
convertListToArrayOfPoses(waypoints, poses);
moveit_msgs::RobotTrajectory trajectory;
GILReleaser gr;
double fraction =
computeCartesianPath(poses, eef_step, jump_threshold, trajectory, path_constraints, avoid_collisions);
gr.reacquire();
double fraction;
{
GILReleaser gr;
fraction = computeCartesianPath(poses, eef_step, jump_threshold, trajectory, path_constraints, avoid_collisions);
}
return bp::make_tuple(py_bindings_tools::serializeMsg(trajectory), fraction);
}

Expand Down Expand Up @@ -540,36 +543,39 @@ class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer
// Convert trajectory message to object
moveit_msgs::RobotTrajectory traj_msg;
py_bindings_tools::deserializeMsg(traj_str, traj_msg);
GILReleaser gr;
robot_trajectory::RobotTrajectory traj_obj(getRobotModel(), getName());
traj_obj.setRobotTrajectoryMsg(ref_state_obj, traj_msg);

// Do the actual retiming
if (algorithm == "iterative_time_parameterization")
{
trajectory_processing::IterativeParabolicTimeParameterization time_param;
time_param.computeTimeStamps(traj_obj, velocity_scaling_factor, acceleration_scaling_factor);
}
else if (algorithm == "iterative_spline_parameterization")
bool algorithm_found = true;
{
trajectory_processing::IterativeSplineParameterization time_param;
time_param.computeTimeStamps(traj_obj, velocity_scaling_factor, acceleration_scaling_factor);
}
else if (algorithm == "time_optimal_trajectory_generation")
{
trajectory_processing::TimeOptimalTrajectoryGeneration time_param;
time_param.computeTimeStamps(traj_obj, velocity_scaling_factor, acceleration_scaling_factor);
}
else
{
ROS_ERROR_STREAM_NAMED("move_group_py", "Unknown time parameterization algorithm: " << algorithm);
gr.reacquire();
return py_bindings_tools::serializeMsg(moveit_msgs::RobotTrajectory());
}
GILReleaser gr;
robot_trajectory::RobotTrajectory traj_obj(getRobotModel(), getName());
traj_obj.setRobotTrajectoryMsg(ref_state_obj, traj_msg);

// Do the actual retiming
if (algorithm == "iterative_time_parameterization")
{
trajectory_processing::IterativeParabolicTimeParameterization time_param;
time_param.computeTimeStamps(traj_obj, velocity_scaling_factor, acceleration_scaling_factor);
}
else if (algorithm == "iterative_spline_parameterization")
{
trajectory_processing::IterativeSplineParameterization time_param;
time_param.computeTimeStamps(traj_obj, velocity_scaling_factor, acceleration_scaling_factor);
}
else if (algorithm == "time_optimal_trajectory_generation")
{
trajectory_processing::TimeOptimalTrajectoryGeneration time_param;
time_param.computeTimeStamps(traj_obj, velocity_scaling_factor, acceleration_scaling_factor);
}
else
{
ROS_ERROR_STREAM_NAMED("move_group_py", "Unknown time parameterization algorithm: " << algorithm);
algorithm_found = false;
traj_msg = moveit_msgs::RobotTrajectory();
}

// Convert the retimed trajectory back into a message
traj_obj.getRobotTrajectoryMsg(traj_msg);
gr.reacquire();
if (algorithm_found)
// Convert the retimed trajectory back into a message
traj_obj.getRobotTrajectoryMsg(traj_msg);
}
return py_bindings_tools::serializeMsg(traj_msg);
}
else
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,13 +59,16 @@ class GILReleaser
/** \brief Release the GIL on construction */
GILReleaser() noexcept
{
m_thread_state = nullptr;
release();
m_thread_state = PyEval_SaveThread();
}
/** \brief Reacquire the GIL on destruction */
~GILReleaser() noexcept
{
reacquire();
if (m_thread_state)
{
PyEval_RestoreThread(m_thread_state);
m_thread_state = nullptr;
}
}

GILReleaser(const GILReleaser&) = delete;
Expand All @@ -87,24 +90,6 @@ class GILReleaser
{
std::swap(other.m_thread_state, m_thread_state);
}

/** \brief Reacquire the GIL, noop if already acquired */
void reacquire() noexcept
{
if (m_thread_state)
{
PyEval_RestoreThread(m_thread_state);
m_thread_state = nullptr;
}
}
/** \brief Release the GIL (again), noop if already released */
void release() noexcept
{
if (!m_thread_state)
{
m_thread_state = PyEval_SaveThread();
}
}
};

} // namespace py_bindings_tools
Expand Down