|
| 1 | +/** |
| 2 | +(C) Copyright 2019-2024 DQ Robotics Developers |
| 3 | +
|
| 4 | +This file is part of DQ Robotics. |
| 5 | +
|
| 6 | + DQ Robotics is free software: you can redistribute it and/or modify |
| 7 | + it under the terms of the GNU Lesser General Public License as published by |
| 8 | + the Free Software Foundation, either version 3 of the License, or |
| 9 | + (at your option) any later version. |
| 10 | +
|
| 11 | + DQ Robotics is distributed in the hope that it will be useful, |
| 12 | + but WITHOUT ANY WARRANTY; without even the implied warranty of |
| 13 | + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
| 14 | + GNU Lesser General Public License for more details. |
| 15 | +
|
| 16 | + You should have received a copy of the GNU Lesser General Public License |
| 17 | + along with DQ Robotics. If not, see <http://www.gnu.org/licenses/>. |
| 18 | +
|
| 19 | +Contributors: |
| 20 | +1. Murilo M. Marinho ([email protected]) |
| 21 | + - Initial implementation. |
| 22 | +
|
| 23 | +*/ |
| 24 | + |
| 25 | +#include "../../dqrobotics_module.h" |
| 26 | + |
| 27 | +//Default arguments added with: |
| 28 | +//https://pybind11.readthedocs.io/en/stable/basics.html#default-args |
| 29 | + |
| 30 | +void init_DQ_CoppeliaSimInterfaceZMQ_py(py::module& m) |
| 31 | +{ |
| 32 | + /***************************************************** |
| 33 | + * VrepInterface |
| 34 | + * **************************************************/ |
| 35 | + py::class_< |
| 36 | + DQ_CoppeliaSimInterfaceZMQ, |
| 37 | + std::shared_ptr<DQ_CoppeliaSimInterfaceZMQ> |
| 38 | + > dqcsinterfacezmq_py(m,"DQ_CoppeliaSimInterfaceZMQ"); |
| 39 | + dqcsinterfacezmq_py.def(py::init<>()); |
| 40 | + |
| 41 | + dqcsinterfacezmq_py.def("connect",(bool (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const int&, const int&, const int&))&DQ_CoppeliaSimInterfaceZMQ::connect,"Connects to CoppeliaSim with a given ip."); |
| 42 | + |
| 43 | + dqcsinterfacezmq_py.def("disconnect", &DQ_CoppeliaSimInterfaceZMQ::disconnect,"Disconnects from CoppeliaSim."); |
| 44 | + dqcsinterfacezmq_py.def("disconnect_all",&DQ_CoppeliaSimInterfaceZMQ::disconnect_all,"Disconnect all from CoppeliaSim"); |
| 45 | + |
| 46 | + dqcsinterfacezmq_py.def("start_simulation",&DQ_CoppeliaSimInterfaceZMQ::start_simulation,"Start simulation"); |
| 47 | + dqcsinterfacezmq_py.def("stop_simulation", &DQ_CoppeliaSimInterfaceZMQ::stop_simulation,"Stops simulation"); |
| 48 | + |
| 49 | + dqcsinterfacezmq_py.def("set_synchronous", (void (DQ_CoppeliaSimInterfaceZMQ::*) (const bool&))&DQ_CoppeliaSimInterfaceZMQ::set_synchronous, "Sets synchronous mode"); |
| 50 | + |
| 51 | + dqcsinterfacezmq_py.def("trigger_next_simulation_step", &DQ_CoppeliaSimInterfaceZMQ::trigger_next_simulation_step, "Sends a synchronization trigger signal to the server."); |
| 52 | + |
| 53 | + dqcsinterfacezmq_py.def("wait_for_simulation_step_to_end", &DQ_CoppeliaSimInterfaceZMQ::wait_for_simulation_step_to_end, "Waits until the simulation step is finished."); |
| 54 | + |
| 55 | + dqcsinterfacezmq_py.def("get_object_translation", |
| 56 | + (DQ (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const std::string&))&DQ_CoppeliaSimInterfaceZMQ::get_object_translation, |
| 57 | + "Gets object translation."); |
| 58 | + |
| 59 | + dqcsinterfacezmq_py.def("set_object_translation", |
| 60 | + (void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const DQ&, const std::string&))&DQ_CoppeliaSimInterfaceZMQ::set_object_translation, |
| 61 | + "Sets object translation."); |
| 62 | + |
| 63 | + dqcsinterfacezmq_py.def("get_object_rotation", |
| 64 | + (DQ (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const std::string&))&DQ_CoppeliaSimInterfaceZMQ::get_object_rotation, |
| 65 | + "Gets object rotation."); |
| 66 | + |
| 67 | + dqcsinterfacezmq_py.def("set_object_rotation", |
| 68 | + (void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const DQ&))&DQ_CoppeliaSimInterfaceZMQ::set_object_rotation, |
| 69 | + "Sets object rotation."); |
| 70 | + |
| 71 | + dqcsinterfacezmq_py.def("get_object_pose", |
| 72 | + (DQ (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const std::string&))&DQ_CoppeliaSimInterfaceZMQ::get_object_pose, |
| 73 | + "Gets object pose."); |
| 74 | + |
| 75 | + dqcsinterfacezmq_py.def("set_object_pose", |
| 76 | + (void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const DQ&, const std::string&))&DQ_CoppeliaSimInterfaceZMQ::set_object_pose, |
| 77 | + "Sets object pose."); |
| 78 | + |
| 79 | + dqcsinterfacezmq_py.def("set_joint_position", |
| 80 | + (void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const double&))&::DQ_CoppeliaSimInterfaceZMQ::set_joint_positions, |
| 81 | + "Set joint position"); |
| 82 | + |
| 83 | + dqcsinterfacezmq_py.def("set_joint_target_position", |
| 84 | + (void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const double&))&DQ_CoppeliaSimInterfaceZMQ::set_joint_target_positions, |
| 85 | + "Set joint target position"); |
| 86 | + |
| 87 | + dqcsinterfacezmq_py.def("get_joint_position", |
| 88 | + (double (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&))&::DQ_CoppeliaSimInterfaceZMQ::get_joint_positions, |
| 89 | + "Get joint position"); |
| 90 | + |
| 91 | + dqcsinterfacezmq_py.def("set_joint_positions", |
| 92 | + (void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::vector<std::string>&, const VectorXd&))&DQ_CoppeliaSimInterfaceZMQ::set_joint_positions, |
| 93 | + "Set joint positions"); |
| 94 | + |
| 95 | + dqcsinterfacezmq_py.def("set_joint_target_positions", |
| 96 | + (void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::vector<std::string>&, const VectorXd&))&DQ_CoppeliaSimInterfaceZMQ::set_joint_target_positions, |
| 97 | + "Set joint positions"); |
| 98 | + |
| 99 | + dqcsinterfacezmq_py.def("get_joint_positions", |
| 100 | + (VectorXd (DQ_CoppeliaSimInterfaceZMQ::*) (const std::vector<std::string>&))&DQ_CoppeliaSimInterfaceZMQ::get_joint_positions, |
| 101 | + "Get joint positions"); |
| 102 | + |
| 103 | +} |
0 commit comments