moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
transforms.cpp
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#include "transforms.hpp"
38
39namespace moveit_py
40{
41namespace bind_transforms
42{
43Eigen::MatrixXd getTransform(std::shared_ptr<moveit::core::Transforms>& transforms, std::string& from_frame)
44{
45 auto transform = transforms->getTransform(from_frame);
46 return transform.matrix();
47}
48
49std::map<std::string, Eigen::MatrixXd> getAllTransforms(std::shared_ptr<moveit::core::Transforms>& transforms)
50{
51 std::map<std::string, Eigen::MatrixXd> transforms_map;
52 for (auto& transform : transforms->getAllTransforms())
53 {
54 transforms_map[transform.first] = transform.second.matrix();
55 }
56 return transforms_map;
57}
58
59void initTransforms(py::module& m)
60{
61 py::module transforms = m.def_submodule("transforms");
62
63 py::class_<moveit::core::Transforms, std::shared_ptr<moveit::core::Transforms>>(transforms, "Transforms",
64 R"(A snapshot of a transform tree.)")
65
66 .def(py::init<std::string&>(), R"(Create a new Transforms object.)", py::arg("target_frame"))
67
68 .def("get_target_frame", &moveit::core::Transforms::getTargetFrame, R"(Get the target frame.)")
69
70 .def("get_transform", &moveit_py::bind_transforms::getTransform, py::arg("from_frame"),
71 R"(Get the transform for from_frame with respect to the target frame.)")
72
73 .def("get_all_transforms", &moveit_py::bind_transforms::getAllTransforms,
74 R"(Get all transforms with respect to the target frame.)");
75
76 // TODO(peterdavidfagan): Add methods for applying transforms.
77}
78
79} // namespace bind_transforms
80} // namespace moveit_py
const std::string & getTargetFrame() const
Get the planning frame corresponding to this set of transforms.
std::map< std::string, Eigen::MatrixXd > getAllTransforms(std::shared_ptr< moveit::core::Transforms > &transforms)
Eigen::MatrixXd getTransform(std::shared_ptr< moveit::core::Transforms > &transforms, std::string &from_frame)
void initTransforms(py::module &m)