moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
rclpy_time_typecaster.hpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2022, Shobin Vinod
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 the copyright holder 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: Shobin Vinod */
36
37#include <pybind11/pybind11.h>
38#include <rclcpp/rclcpp.hpp>
39#include <rclcpp/serialization.hpp>
40#include <rclcpp/duration.hpp>
41
42namespace py = pybind11;
43
44namespace pybind11
45{
46namespace detail
47{
48template <>
49struct type_caster<rclcpp::Time>
50{
51 PYBIND11_TYPE_CASTER(rclcpp::Time, _("rclcpp::Time"));
52
53 // convert from rclpy::Time to rclcpp::Time
54 bool load(py::handle src, bool)
55 {
56 if (src.is_none())
57 return false;
58
59 // check to validate if the object is a rclcpp::Time object
60 if (!py::hasattr(src, "nanoseconds") || !py::hasattr(src, "clock_type"))
61 {
62 return false;
63 }
64
65 // Extract the value for constructing the rclcpp::Time object
66 int64_t nanoseconds = src.attr("nanoseconds").cast<int64_t>();
67 int clock_type = src.attr("clock_type").cast<int>();
68
69 // Construct the rclcpp::Time object
70 value = rclcpp::Time(nanoseconds, static_cast<rcl_clock_type_t>(clock_type));
71 return true;
72 }
73
74 // convert from rclcpp::Time to rclpy::Time
75 static py::handle cast(const rclcpp::Time& src, return_value_policy /* policy */, py::handle /* parent */)
76 {
77 py::module rclpy_time = py::module::import("rclpy.time");
78 py::object Time = rclpy_time.attr("Time");
79
80 int64_t nanoseconds = src.nanoseconds();
81 int clock_type = static_cast<int>(src.get_clock_type());
82
83 return Time(py::arg("nanoseconds") = nanoseconds,
84 py::arg("clock_type") = clock_type)
85 .release(); // release the ownership of the object
86 }
87};
88} // namespace detail
89} // namespace pybind11
static py::handle cast(const rclcpp::Time &src, return_value_policy, py::handle)
PYBIND11_TYPE_CASTER(rclcpp::Time, _("rclcpp::Time"))