Upgrade pybind11 to v3

This commit is contained in:
Robert Haschke 2025-05-02 10:46:07 +02:00
parent c6521551a4
commit d19b77782d
6 changed files with 4 additions and 65 deletions

View File

@ -1,14 +1,10 @@
#pragma once
#include <pybind11/smart_holder.h>
#include <py_binding_tools/ros_msg_typecasters.h>
#include <moveit/task_constructor/properties.h>
#include <boost/any.hpp>
#include <typeindex>
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::Property)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::PropertyMap)
namespace moveit {
namespace python {
@ -59,7 +55,7 @@ class class_ : public pybind11::classh<type_, options...> // NOLINT(readability
public:
// forward all constructors
using base_class_::classh;
using base_class_::class_;
template <typename PropertyType, typename... Extra>
class_& property(const char* name, const Extra&... extra) {

View File

@ -39,7 +39,7 @@
#include <moveit/task_constructor/cost_queue.h>
#include <moveit/task_constructor/cost_terms.h>
#include <moveit/utils/moveit_error_code.h>
#include <pybind11/smart_holder.h>
#include <pybind11/pybind11.h>
/** Trampoline classes to allow inheritance in Python (overriding virtual functions) */
@ -108,36 +108,3 @@ public:
} // namespace task_constructor
} // namespace moveit
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::solvers::PlannerInterface)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::SolutionBase)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::SubTrajectory)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(ordered<moveit::task_constructor::SolutionBaseConstPtr>)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::InterfaceState)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::core::MoveItErrorCode)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::CostTerm)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::TrajectoryCostTerm)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::cost::PathLength)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::cost::DistanceToReference)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::cost::TrajectoryDuration)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::cost::LinkMotion)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::cost::Clearance)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::Stage)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::PropagatingEitherWay)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::PropagatingForward)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::PropagatingBackward)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::Generator)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::MonitoringGenerator)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::ContainerBase)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::SerialContainer)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::ParallelContainerBase)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::Alternatives)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::Fallbacks)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::Merger)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::WrapperBase)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::Task)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(moveit::task_constructor::Introspection)

View File

@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
#include <pybind11/smart_holder.h>
#include <pybind11/pybind11.h>
namespace moveit {
namespace python {

View File

@ -46,12 +46,6 @@ using namespace py::literals;
using namespace moveit::task_constructor;
using namespace moveit::task_constructor::solvers;
PYBIND11_SMART_HOLDER_TYPE_CASTERS(PlannerInterface)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(PipelinePlanner)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(JointInterpolationPlanner)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(CartesianPath)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(MultiPlanner)
namespace moveit {
namespace python {

View File

@ -47,24 +47,6 @@ using namespace py::literals;
using namespace moveit::task_constructor;
using namespace moveit::task_constructor::stages;
PYBIND11_SMART_HOLDER_TYPE_CASTERS(ModifyPlanningScene)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(CurrentState)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(FixedState)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(ComputeIK)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(MoveTo)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(MoveRelative)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(Connect)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(FixCollisionObjects)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(GenerateGraspPose)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(GeneratePlacePose)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(GenerateRandomPose)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(GeneratePose)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(Pick)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(Place)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(SimpleGraspBase)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(SimpleGrasp)
PYBIND11_SMART_HOLDER_TYPE_CASTERS(SimpleUnGrasp)
namespace moveit {
namespace python {

@ -1 +1 @@
Subproject commit f4bc71f981d4eb2dd780215fd3c5a7420f1f03aa
Subproject commit ed5057ded698e305210269dafa57574ecf964483