Skip to content

Commit

Permalink
rolled back change moveit#1100
Browse files Browse the repository at this point in the history
  • Loading branch information
masf7g committed Mar 16, 2022
1 parent baeb83a commit 196975f
Showing 1 changed file with 11 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -404,17 +404,6 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost:
*/
bool waitForCurrentRobotState(const rclcpp::Time& t, double wait_time = 1.);

void clearOctomap();

// Called to update the planning scene with a new message.
bool newPlanningSceneMessage(const moveit_msgs::msg::PlanningScene& scene);

protected:
/** @brief Initialize the planning scene monitor
* @param scene The scene instance to fill with data (an instance is allocated if the one passed in is not allocated)
*/
void initialize(const planning_scene::PlanningScenePtr& scene);

/** \brief Lock the scene for reading (multiple threads can lock for reading at the same time) */
void lockSceneRead();

Expand All @@ -429,6 +418,17 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor : private boost:
*/
void unlockSceneWrite();

void clearOctomap();

// Called to update the planning scene with a new message.
bool newPlanningSceneMessage(const moveit_msgs::msg::PlanningScene& scene);

protected:
/** @brief Initialize the planning scene monitor
* @param scene The scene instance to fill with data (an instance is allocated if the one passed in is not allocated)
*/
void initialize(const planning_scene::PlanningScenePtr& scene);

/** @brief Configure the collision matrix for a particular scene */
void configureCollisionMatrix(const planning_scene::PlanningScenePtr& scene);

Expand Down

0 comments on commit 196975f

Please sign in to comment.