37 #include <pybind11/pybind11.h>
38 #include <pybind11/eigen.h>
39 #include <pybind11/stl.h>
40 #include <rclcpp/rclcpp.hpp>
42 #include <moveit_msgs/msg/constraints.hpp>
48 namespace bind_kinematic_constraints
50 moveit_msgs::msg::Constraints
constructLinkConstraint(
const std::string& link_name,
const std::string& source_frame,
51 std::optional<std::vector<double>> cartesian_position,
52 std::optional<double> cartesian_position_tolerance,
53 std::optional<std::vector<double>> orientation,
54 std::optional<double> orientation_tolerance);
61 const std::string& ns);
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void initKinematicConstraints(py::module &m)
moveit_msgs::msg::Constraints constructJointConstraint(moveit::core::RobotState &robot_state, moveit::core::JointModelGroup *joint_model_group, double tolerance)
moveit_msgs::msg::Constraints constructConstraintsFromNode(const std::shared_ptr< rclcpp::Node > &node_name, const std::string &ns)
moveit_msgs::msg::Constraints constructLinkConstraint(const std::string &link_name, const std::string &source_frame, std::optional< std::vector< double >> cartesian_position, std::optional< double > cartesian_position_tolerance, std::optional< std::vector< double >> orientation, std::optional< double > orientation_tolerance)