moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_scene_monitor.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2022, Peter David Fagan
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of PickNik Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Peter David Fagan */
36 
37 #pragma once
38 
39 #include <pybind11/pybind11.h>
40 #include <pybind11/stl.h>
43 #include <rclcpp/rclcpp.hpp>
44 #include <moveit_msgs/msg/planning_scene.hpp>
45 #include <moveit_msgs/srv/apply_planning_scene.hpp>
47 
48 namespace py = pybind11;
49 
50 namespace moveit_py
51 {
52 namespace bind_planning_scene_monitor
53 {
55 {
56 public:
57  const planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
58  std::unique_ptr<const planning_scene_monitor::LockedPlanningSceneRW> ls_rw_;
59 
60  LockedPlanningSceneContextManagerRW(const planning_scene_monitor::PlanningSceneMonitorPtr& psm)
62  {
63  ls_rw_ = std::make_unique<const planning_scene_monitor::LockedPlanningSceneRW>(planning_scene_monitor_);
64  }
65 
66  const planning_scene::PlanningScenePtr& lockedPlanningSceneRwEnter();
67 
68  void lockedPlanningSceneRwExit(const py::object& type, const py::object& value, const py::object& traceback);
69 };
70 
72 {
73 public:
74  const planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
75  std::unique_ptr<const planning_scene_monitor::LockedPlanningSceneRO> ls_ro_;
76 
77  LockedPlanningSceneContextManagerRO(const planning_scene_monitor::PlanningSceneMonitorPtr& psm)
79  {
80  ls_ro_ = std::make_unique<const planning_scene_monitor::LockedPlanningSceneRO>(planning_scene_monitor_);
81  }
82 
83  const planning_scene::PlanningSceneConstPtr& lockedPlanningSceneRoEnter() const;
84 
85  void lockedPlanningSceneRoExit(const py::object& type, const py::object& value, const py::object& traceback);
86 };
87 
88 LockedPlanningSceneContextManagerRW
89 readWrite(const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor);
90 
91 LockedPlanningSceneContextManagerRO
92 readOnly(const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor);
93 
94 void initPlanningSceneMonitor(py::module& m);
95 
96 void initContextManagers(py::module& m);
97 } // namespace bind_planning_scene_monitor
98 } // namespace moveit_py
const planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
const planning_scene::PlanningSceneConstPtr & lockedPlanningSceneRoEnter() const
void lockedPlanningSceneRoExit(const py::object &type, const py::object &value, const py::object &traceback)
std::unique_ptr< const planning_scene_monitor::LockedPlanningSceneRO > ls_ro_
LockedPlanningSceneContextManagerRO(const planning_scene_monitor::PlanningSceneMonitorPtr &psm)
const planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
LockedPlanningSceneContextManagerRW(const planning_scene_monitor::PlanningSceneMonitorPtr &psm)
std::unique_ptr< const planning_scene_monitor::LockedPlanningSceneRW > ls_rw_
void lockedPlanningSceneRwExit(const py::object &type, const py::object &value, const py::object &traceback)
LockedPlanningSceneContextManagerRW readWrite(const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
LockedPlanningSceneContextManagerRO readOnly(const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)