Skip to content

Commit

Permalink
Remove mutex and thread safety TODOs
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr committed Aug 17, 2022
1 parent fa43563 commit a77aea4
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,6 @@
#include <moveit/robot_state/conversions.h>
#include <moveit/utils/moveit_error_code.h>

#include <mutex>

namespace moveit_cpp
{
MOVEIT_CLASS_FORWARD(PlanningComponent); // Defines PlanningComponentPtr, ConstPtr, WeakPtr... etc
Expand Down Expand Up @@ -248,7 +246,7 @@ class PlanningComponent
private:
// Core properties and instances
rclcpp::Node::SharedPtr node_;
MoveItCppPtr moveit_cpp_; // TODO Make thread safe!
MoveItCppPtr moveit_cpp_;
const std::string group_name_;
// The robot_model_ member variable of MoveItCpp class will manually free the joint_model_group_ resources
const moveit::core::JointModelGroup* joint_model_group_;
Expand All @@ -264,7 +262,7 @@ class PlanningComponent
PlanRequestParameters plan_request_parameters_;
moveit_msgs::msg::WorkspaceParameters workspace_parameters_;
bool workspace_parameters_set_ = false;
PlanSolutionPtr last_plan_solution_; // TODO Make thread safe!
PlanSolutionPtr last_plan_solution_;

// common properties for goals
// TODO(henningkayser): support goal tolerances
Expand Down
1 change: 0 additions & 1 deletion moveit_ros/planning/moveit_cpp/src/planning_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,6 @@ bool PlanningComponent::setPathConstraints(const moveit_msgs::msg::Constraints&
PlanningComponent::PlanSolution PlanningComponent::plan(const PlanRequestParameters& parameters,
const bool update_last_solution)
{
std::lock_guard<std::mutex> lock_guard(plan_mutex_);
// check if joint_model_group exists
auto plan_solution = std::make_shared<PlanSolution>();
if (!joint_model_group_)
Expand Down

0 comments on commit a77aea4

Please sign in to comment.