moveit2
The MoveIt Motion Planning Framework for ROS 2.
pymoveit_core.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, Peter Mitrano
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  * * The name of Peter Mitrano may not be used to endorse or promote
18  * products derived from this software without specific prior
19  * 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 Mitrano */
36 
37 #include <pybind11/pybind11.h>
38 #include <urdf_parser/urdf_parser.h>
40 #include <srdfdom/model.h>
41 
42 namespace py = pybind11;
43 
44 // Each of these functions defines the bindings for a namespace/subfolder within moveit_core
45 void def_collision_detection_bindings(py::module& contact);
46 
47 void def_robot_model_bindings(py::module& m);
48 
49 void def_robot_state_bindings(py::module& m);
50 
51 void def_transforms_bindings(py::module& m);
52 
53 void def_planning_scene_bindings(py::module& m);
54 
55 void def_kinematic_constraints_bindings(py::module& m);
56 
57 auto load_robot_model(const std::string& urdf_path, const std::string& srdf_path)
58 {
59  auto urdf_model = urdf::parseURDFFile(urdf_path);
60  auto srdf_model = std::make_shared<srdf::Model>();
61  srdf_model->initFile(*urdf_model, srdf_path);
62  auto robot_model = std::make_shared<moveit::core::RobotModel>(urdf_model, srdf_model);
63  return robot_model;
64 }
65 
66 PYBIND11_MODULE(pymoveit_core, m)
67 {
68  auto collision_detection_m = m.def_submodule("collision_detection");
69  auto planning_scene_m = m.def_submodule("planning_scene");
70  auto robot_model_m = m.def_submodule("robot_model");
71  auto robot_state_m = m.def_submodule("robot_state");
72  auto kinematic_constraints_m = m.def_submodule("kinematic_constraints");
73  auto transforms_m = m.def_submodule("transforms");
74 
75  def_collision_detection_bindings(collision_detection_m);
76  def_robot_model_bindings(robot_model_m);
77  def_robot_state_bindings(robot_state_m);
78  def_planning_scene_bindings(planning_scene_m);
79  def_transforms_bindings(transforms_m);
80  def_kinematic_constraints_bindings(kinematic_constraints_m);
81 
82  // convenience function
83  m.def("load_robot_model", &load_robot_model);
84 }
void def_transforms_bindings(py::module &m)
void def_robot_model_bindings(py::module &m)
auto load_robot_model(const std::string &urdf_path, const std::string &srdf_path)
void def_robot_state_bindings(py::module &m)
PYBIND11_MODULE(pymoveit_core, m)
void def_collision_detection_bindings(py::module &contact)
void def_planning_scene_bindings(py::module &m)
void def_kinematic_constraints_bindings(py::module &m)