moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
planning_response.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 "planning_response.h"
38
39namespace moveit_py
40{
41namespace bind_planning_interface
42{
43std::shared_ptr<robot_trajectory::RobotTrajectory>
44getMotionPlanResponseTrajectory(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
45{
46 return response->trajectory;
47}
48
49moveit_msgs::msg::RobotState
50getMotionPlanResponseStartState(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
51{
52 moveit_msgs::msg::RobotState robot_state_msg = response->start_state;
53 return robot_state_msg;
54}
55
56moveit_msgs::msg::MoveItErrorCodes
57getMotionPlanResponseErrorCode(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
58{
59 moveit_msgs::msg::MoveItErrorCodes error_code_msg =
60 static_cast<moveit_msgs::msg::MoveItErrorCodes>(response->error_code);
61 return error_code_msg;
62}
63
64double getMotionPlanResponsePlanningTime(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
65{
66 return response->planning_time;
67}
68
69std::string getMotionPlanResponsePlannerId(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
70{
71 return response->planner_id;
72}
73
74void initMotionPlanResponse(py::module& m)
75{
76 py::module planning_interface = m.def_submodule("planning_interface");
77
78 py::class_<planning_interface::MotionPlanResponse, std::shared_ptr<planning_interface::MotionPlanResponse>>(
79 planning_interface, "MotionPlanResponse", R"()")
80
81 //.def(py::init<>(), R"()")
82
84 py::return_value_policy::copy, R"()")
85
86 .def_readonly("planning_time", &planning_interface::MotionPlanResponse::planning_time,
87 py::return_value_policy::copy, R"()")
88
90 py::return_value_policy::copy, R"()")
91
93 py::return_value_policy::copy, R"()")
94
95 .def_readonly("planner_id", &planning_interface::MotionPlanResponse::planner_id, py::return_value_policy::copy,
96 R"()")
97
98 .def("__bool__", [](std::shared_ptr<planning_interface::MotionPlanResponse>& response) {
99 return response->error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
100 });
101}
102} // namespace bind_planning_interface
103} // namespace moveit_py
std::shared_ptr< robot_trajectory::RobotTrajectory > getMotionPlanResponseTrajectory(std::shared_ptr< planning_interface::MotionPlanResponse > &response)
moveit_msgs::msg::MoveItErrorCodes getMotionPlanResponseErrorCode(std::shared_ptr< planning_interface::MotionPlanResponse > &response)
moveit_msgs::msg::RobotState getMotionPlanResponseStartState(std::shared_ptr< planning_interface::MotionPlanResponse > &response)
double getMotionPlanResponsePlanningTime(std::shared_ptr< planning_interface::MotionPlanResponse > &response)
std::string getMotionPlanResponsePlannerId(std::shared_ptr< planning_interface::MotionPlanResponse > &response)
This namespace includes the base class for MoveIt planners.