Skip to content

Commit

Permalink
adding support for multi pipeline planning
Browse files Browse the repository at this point in the history
  • Loading branch information
peterdavidfagan committed Jan 1, 2023
1 parent acf41e6 commit 01d5dc8
Show file tree
Hide file tree
Showing 13 changed files with 387 additions and 145 deletions.
2 changes: 2 additions & 0 deletions moveit_py/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ pybind11_add_module(core
src/moveit_py/core.cpp
src/moveit_py/moveit_core/collision_detection/collision_common.cpp
src/moveit_py/moveit_core/collision_detection/collision_matrix.cpp
src/moveit_py/moveit_core/planning_interface/planning_response.cpp
src/moveit_py/moveit_core/planning_scene/planning_scene.cpp
src/moveit_py/moveit_core/transforms/transforms.cpp
src/moveit_py/moveit_core/robot_model/joint_model_group.cpp
Expand All @@ -35,6 +36,7 @@ pybind11_add_module(core
target_link_libraries(core PRIVATE moveit_ros_planning::moveit_cpp
rclcpp::rclcpp
moveit_core::moveit_transforms
moveit_core::moveit_planning_interface
moveit_core::moveit_planning_scene
moveit_core::moveit_utils
moveit_core::moveit_robot_model
Expand Down
2 changes: 2 additions & 0 deletions moveit_py/src/moveit_py/core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#include "moveit_core/robot_trajectory/robot_trajectory.h"
#include "moveit_core/collision_detection/collision_common.h"
#include "moveit_core/collision_detection/collision_matrix.h"
#include "moveit_core/planning_interface/planning_response.h"
#include "moveit_core/planning_scene/planning_scene.h"

PYBIND11_MODULE(core, m)
Expand All @@ -61,6 +62,7 @@ PYBIND11_MODULE(core, m)
moveit_py::bind_collision_detection::init_collision_result(m);
moveit_py::bind_collision_detection::init_acm(m);
moveit_py::bind_planning_scene::init_planning_scene(m);
moveit_py::bind_planning_interface::init_motion_plan_response(m);

// TODO (peterdavidfagan): complete LinkModel bindings
// LinkModel
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,112 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2022, Peter David Fagan
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of PickNik Inc. nor te names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Author: Peter David Fagan */

#include "planning_response.h"

namespace moveit_py
{
namespace bind_planning_interface
{

std::shared_ptr<robot_trajectory::RobotTrajectory>
get_motion_plan_response_trajectory(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
{
return response->trajectory_;
}

py::object get_motion_plan_response_start_state(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
{
py::module_ rclpy_serialization = py::module_::import("rclpy.serialization");
py::module_ moveit_msgs = py::module_::import("moveit_msgs.msg");

py::object robot_state = moveit_msgs.attr("RobotState")();
moveit_msgs::msg::RobotState robot_state_msg = response->start_state_;
py::bytes serialized_msg = serializeMsg(robot_state_msg);
rclpy_serialization.attr("deserialize_message")(serialized_msg, robot_state);
return robot_state;
}

py::object get_motion_plan_response_error_code(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
{
py::module_ rclpy_serialization = py::module_::import("rclpy.serialization");
py::module_ moveit_msgs = py::module_::import("moveit_msgs.msg");

py::object error_code = moveit_msgs.attr("MoveItErrorCodes")();
moveit_msgs::msg::MoveItErrorCodes error_code_msg =
static_cast<moveit_msgs::msg::MoveItErrorCodes>(response->error_code_);
py::bytes serialized_msg = serializeMsg(error_code_msg);
rclpy_serialization.attr("deserialize_message")(serialized_msg, error_code);
return error_code;
}

double get_motion_plan_response_planning_time(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
{
return response->planning_time_;
}

std::string get_motion_plan_response_planner_id(std::shared_ptr<planning_interface::MotionPlanResponse>& response)
{
return response->planner_id_;
}

void init_motion_plan_response(py::module& m)
{
py::class_<planning_interface::MotionPlanResponse, std::shared_ptr<planning_interface::MotionPlanResponse>>(
m, "MotionPlanResponse", R"()")

//.def(py::init<>(), R"()")

.def_property("trajectory", &moveit_py::bind_planning_interface::get_motion_plan_response_trajectory, nullptr,
py::return_value_policy::copy, R"()")

.def_readonly("planning_time", &planning_interface::MotionPlanResponse::planning_time_,
py::return_value_policy::copy, R"()")

.def_property("error_code", &moveit_py::bind_planning_interface::get_motion_plan_response_error_code, nullptr,
py::return_value_policy::copy, R"()")

.def_property("start_state", &moveit_py::bind_planning_interface::get_motion_plan_response_start_state, nullptr,
py::return_value_policy::copy, R"()")

.def_readonly("planner_id", &planning_interface::MotionPlanResponse::planner_id_, py::return_value_policy::copy,
R"()")

.def("__bool__", [](std::shared_ptr<planning_interface::MotionPlanResponse>& response) {
return response->error_code_.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
});
}
} // namespace bind_planning_interface
} // namespace moveit_py
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2022, Peter David Fagan
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of PickNik Inc. nor te names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Author: Peter David Fagan */

#pragma once

#include <pybind11/pybind11.h>
#include <pybind11/eigen.h>
#include <pybind11/stl.h>
#include <moveit_msgs/msg/robot_state.h>
#include <moveit_msgs/msg/move_it_error_codes.h>
#include <serialize_ros_msg.h>
#include <moveit/planning_interface/planning_response.h>

namespace py = pybind11;

namespace moveit_py
{
namespace bind_planning_interface
{

std::shared_ptr<robot_trajectory::RobotTrajectory>
get_motion_plan_response_trajectory(std::shared_ptr<planning_interface::MotionPlanResponse>& response);

py::object get_motion_plan_response_start_state(std::shared_ptr<planning_interface::MotionPlanResponse>& response);

py::object get_motion_plan_response_error_code(std::shared_ptr<planning_interface::MotionPlanResponse>& response);

double get_motion_plan_response_planning_time(std::shared_ptr<planning_interface::MotionPlanResponse>& response);

std::string get_motion_plan_response_planner_id(std::shared_ptr<planning_interface::MotionPlanResponse>& response);

void init_motion_plan_response(py::module& m);
} // namespace bind_planning_interface
} // namespace moveit_py
41 changes: 0 additions & 41 deletions moveit_py/src/moveit_py/moveit_ros/moveit_cpp/moveit_cpp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,37 +47,6 @@ get_planning_component(std::shared_ptr<moveit_cpp::MoveItCpp>& moveit_cpp_ptr, s
return std::make_shared<moveit_cpp::PlanningComponent>(planning_component, moveit_cpp_ptr);
}

py::object get_plan_solution_start_state(std::shared_ptr<moveit_cpp::PlanningComponent::PlanSolution>& plan_solution)
{
py::module_ rclpy_serialization = py::module::import("rclpy.serialization");
py::module_ moveit_msgs = py::module::import("moveit_msgs.msg");

py::object robot_state = moveit_msgs.attr("RobotState")();
moveit_msgs::msg::RobotState robot_state_cpp = plan_solution->start_state;
py::bytes serialized_msg = serializeMsg(robot_state_cpp);
rclpy_serialization.attr("deserialize_message")(serialized_msg, robot_state);
return robot_state;
}

std::shared_ptr<robot_trajectory::RobotTrajectory>
get_plan_solution_trajectory(std::shared_ptr<moveit_cpp::PlanningComponent::PlanSolution>& plan_solution)
{
return plan_solution->trajectory;
}

py::object get_plan_solution_error_code(std::shared_ptr<moveit_cpp::PlanningComponent::PlanSolution>& plan_solution)
{
py::module_ rclpy_serialization = py::module::import("rclpy.serialization");
py::module_ moveit_msgs = py::module::import("moveit_msgs.msg");

py::object moveit_error_codes = moveit_msgs.attr("MoveItErrorCodes")();
moveit_msgs::msg::MoveItErrorCodes error_codes_cpp =
static_cast<moveit_msgs::msg::MoveItErrorCodes>(plan_solution->error_code);
py::bytes serialized_msg = serializeMsg(error_codes_cpp);
rclpy_serialization.attr("deserialize_message")(serialized_msg, moveit_error_codes);
return moveit_error_codes;
}

void init_moveit_py(py::module& m)
{
auto utils = py::module::import("moveit_py.utils");
Expand Down Expand Up @@ -167,16 +136,6 @@ void init_moveit_py(py::module& m)
:py:class:`moveit_py.planning.PlanningComponent`: A planning component instance corresponding to the provided plan component name.
)")

.def("get_planning_pipeline_names", &moveit_cpp::MoveItCpp::getPlanningPipelineNames,
py::arg("joint_model_group_name"), py::return_value_policy::move,
R"(
Return list of planning pipeline names for the provided joint model group name.
Args:
joint_model_group_name (str): The name of the joint model group.
Returns:
list of str: List of planning pipeline names.
)")

.def(
"shutdown", [](std::shared_ptr<moveit_cpp::MoveItCpp>& moveit_cpp) { rclcpp::shutdown(); },
R"(
Expand Down
8 changes: 0 additions & 8 deletions moveit_py/src/moveit_py/moveit_ros/moveit_cpp/moveit_cpp.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,14 +57,6 @@ namespace bind_moveit_cpp
{
std::shared_ptr<moveit_cpp::PlanningComponent>
get_planning_component(std::shared_ptr<moveit_cpp::MoveItCpp>& moveit_cpp_ptr, std::string planning_component);

py::object get_plan_solution_start_state(std::shared_ptr<moveit_cpp::PlanningComponent::PlanSolution>& plan_solution);

std::shared_ptr<robot_trajectory::RobotTrajectory>
get_plan_solution_trajectory(std::shared_ptr<moveit_cpp::PlanningComponent::PlanSolution>& plan_solution);

py::object get_plan_solution_error_code(std::shared_ptr<moveit_cpp::PlanningComponent::PlanSolution>& plan_solution);

void init_moveit_py(py::module &m);
} // namespace bind_moveit_cpp
} // namespace moveit_py
Loading

0 comments on commit 01d5dc8

Please sign in to comment.