Skip to content

Commit c2acba1

Browse files
authored
Add set_stepping_mode, get_object_handles, remove extra string from signatures, and remove protected C++ methods. Fix #62, Fix #61, and Fix #60 (#63)
* [DQ_CoppeliaSimInterfaceZMQ_py.cpp] Updated the copyright year and added the default connect method. * [DQ_CoppeliaSimInterfaceZMQ_py.cpp] Added the set_stepping_mode. * [DQ_CoppeliaSimInterfaceZMQ_py.cpp] Added the methdos get_object_handles{s}. * [DQ_CoppeliaSimInterfaceZMQ_py.cpp] Removed the bindings of protected C++ methods as set_joint_position, get_joint_position. * [DQ_CoppeliaSimInterfaceZMQ_py.cpp] Fixed the signature of some bindings as set and get object pose. * [DQ_CoppeliaSimInterfaceZMQ_py.cpp] Added default arguments in the connect method
1 parent 9acf13e commit c2acba1

File tree

1 file changed

+37
-13
lines changed

1 file changed

+37
-13
lines changed

src/interfaces/coppeliasim/DQ_CoppeliaSimInterfaceZMQ_py.cpp

+37-13
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
/**
2-
(C) Copyright 2019-2024 DQ Robotics Developers
2+
(C) Copyright 2019-2025 DQ Robotics Developers
33
44
This file is part of DQ Robotics.
55
@@ -20,6 +20,11 @@ This file is part of DQ Robotics.
2020
1. Murilo M. Marinho ([email protected])
2121
- Initial implementation.
2222
23+
2. Juan Jose Quiroz Omana ([email protected])
24+
- Added bindings for the following methods
25+
set_stepping_mode(), get_object_handle(), get_object_handle()
26+
get_joint_{velocities, torques}(), set_joint_target_velocities(),set_joint_torques()
27+
2328
*/
2429

2530
#include "../../dqrobotics_module.h"
@@ -38,6 +43,9 @@ void init_DQ_CoppeliaSimInterfaceZMQ_py(py::module& m)
3843
> dqcsinterfacezmq_py(m,"DQ_CoppeliaSimInterfaceZMQ");
3944
dqcsinterfacezmq_py.def(py::init<>());
4045

46+
dqcsinterfacezmq_py.def("connect",(bool (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const int&, const int&))&DQ_CoppeliaSimInterfaceZMQ::connect,
47+
py::arg("host") = "localhost", py::arg("port") = 23000, py::arg("TIMEOUT_IN_MILISECONDS") = 2000,
48+
"establishes a connection between the client (your code) and the host (the computer running the CoppeliaSim scene.");
4149
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.");
4250

4351
dqcsinterfacezmq_py.def("disconnect", &DQ_CoppeliaSimInterfaceZMQ::disconnect,"Disconnects from CoppeliaSim.");
@@ -46,6 +54,7 @@ void init_DQ_CoppeliaSimInterfaceZMQ_py(py::module& m)
4654
dqcsinterfacezmq_py.def("start_simulation",&DQ_CoppeliaSimInterfaceZMQ::start_simulation,"Start simulation");
4755
dqcsinterfacezmq_py.def("stop_simulation", &DQ_CoppeliaSimInterfaceZMQ::stop_simulation,"Stops simulation");
4856

57+
dqcsinterfacezmq_py.def("set_stepping_mode", (void (DQ_CoppeliaSimInterfaceZMQ::*) (const bool&))&DQ_CoppeliaSimInterfaceZMQ::set_stepping_mode, "enables or disables the stepping mode (formerly known as synchronous mode).");
4958
dqcsinterfacezmq_py.def("set_synchronous", (void (DQ_CoppeliaSimInterfaceZMQ::*) (const bool&))&DQ_CoppeliaSimInterfaceZMQ::set_synchronous, "Sets synchronous mode");
5059

5160
dqcsinterfacezmq_py.def("trigger_next_simulation_step", &DQ_CoppeliaSimInterfaceZMQ::trigger_next_simulation_step, "Sends a synchronization trigger signal to the server.");
@@ -57,7 +66,7 @@ void init_DQ_CoppeliaSimInterfaceZMQ_py(py::module& m)
5766
"Gets object translation.");
5867

5968
dqcsinterfacezmq_py.def("set_object_translation",
60-
(void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const DQ&, const std::string&))&DQ_CoppeliaSimInterfaceZMQ::set_object_translation,
69+
(void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const DQ&))&DQ_CoppeliaSimInterfaceZMQ::set_object_translation,
6170
"Sets object translation.");
6271

6372
dqcsinterfacezmq_py.def("get_object_rotation",
@@ -73,20 +82,16 @@ void init_DQ_CoppeliaSimInterfaceZMQ_py(py::module& m)
7382
"Gets object pose.");
7483

7584
dqcsinterfacezmq_py.def("set_object_pose",
76-
(void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const DQ&, const std::string&))&DQ_CoppeliaSimInterfaceZMQ::set_object_pose,
85+
(void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&, const DQ&))&DQ_CoppeliaSimInterfaceZMQ::set_object_pose,
7786
"Sets object pose.");
7887

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");
88+
dqcsinterfacezmq_py.def("get_object_handle",
89+
(int (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&))&::DQ_CoppeliaSimInterfaceZMQ::get_object_handle,
90+
"gets the object handle from CoppeliaSim.");
8691

87-
dqcsinterfacezmq_py.def("get_joint_position",
88-
(double (DQ_CoppeliaSimInterfaceZMQ::*) (const std::string&))&::DQ_CoppeliaSimInterfaceZMQ::get_joint_positions,
89-
"Get joint position");
92+
dqcsinterfacezmq_py.def("get_object_handles",
93+
(VectorXd (DQ_CoppeliaSimInterfaceZMQ::*) (const std::vector<std::string>&))&DQ_CoppeliaSimInterfaceZMQ::get_object_handles,
94+
"returns a vector containing the object handles.");
9095

9196
dqcsinterfacezmq_py.def("set_joint_positions",
9297
(void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::vector<std::string>&, const VectorXd&))&DQ_CoppeliaSimInterfaceZMQ::set_joint_positions,
@@ -100,4 +105,23 @@ void init_DQ_CoppeliaSimInterfaceZMQ_py(py::module& m)
100105
(VectorXd (DQ_CoppeliaSimInterfaceZMQ::*) (const std::vector<std::string>&))&DQ_CoppeliaSimInterfaceZMQ::get_joint_positions,
101106
"Get joint positions");
102107

108+
dqcsinterfacezmq_py.def("get_joint_velocities",
109+
(VectorXd (DQ_CoppeliaSimInterfaceZMQ::*) (const std::vector<std::string>&))&DQ_CoppeliaSimInterfaceZMQ::get_joint_velocities,
110+
"gets the joint velocities in the CoppeliaSim scene.");
111+
112+
dqcsinterfacezmq_py.def("set_joint_target_velocities",
113+
(void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::vector<std::string>&, const VectorXd&))&DQ_CoppeliaSimInterfaceZMQ::set_joint_target_velocities,
114+
"sets the joint target velocities in the CoppeliaSim scene. "
115+
"This method requires a dynamics enabled scene, and joints in dynamic mode with velocity control mode.");
116+
117+
dqcsinterfacezmq_py.def("get_joint_torques",
118+
(VectorXd (DQ_CoppeliaSimInterfaceZMQ::*) (const std::vector<std::string>&))&DQ_CoppeliaSimInterfaceZMQ::get_joint_torques,
119+
"gets the joint torques in the CoppeliaSim scene.");
120+
121+
dqcsinterfacezmq_py.def("set_joint_torques",
122+
(void (DQ_CoppeliaSimInterfaceZMQ::*) (const std::vector<std::string>&, const VectorXd&))&DQ_CoppeliaSimInterfaceZMQ::set_joint_torques,
123+
"sets the joint torques in the CoppeliaSim scene. "
124+
"This method requires a dynamics enabled scene, and joints in dynamic mode with force control mode.");
125+
126+
103127
}

0 commit comments

Comments
 (0)