Skip to content

Commit 3fdebcc

Browse files
author
Murilo M. Marinho
committed
Adding [DQ_CoppeliaSimInterface_py.cpp] with the wrapper for DQ_CoppeliaSimInterface.
1 parent af6716d commit 3fdebcc

File tree

5 files changed

+94
-6
lines changed

5 files changed

+94
-6
lines changed

src/dqrobotics_module.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -170,6 +170,9 @@ PYBIND11_MODULE(_dqrobotics, m) {
170170
py::module coppeliasim_py = interfaces_py.def_submodule("_coppeliasim", "The CoppeliaSim submodule of DQ Robotics.");
171171

172172
//DQ_CoppeliaSimInterface
173+
init_DQ_CoppeliaSimInterface_py(coppeliasim_py);
174+
175+
//DQ_CoppeliaSimInterfaceZMQ
173176
init_DQ_CoppeliaSimInterfaceZMQ_py(coppeliasim_py);
174177
}
175178

src/dqrobotics_module.h

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,4 @@
1+
#pragma once
12
/**
23
(C) Copyright 2019 DQ Robotics Developers
34
@@ -20,9 +21,6 @@ This file is part of DQ Robotics.
2021
- Murilo M. Marinho ([email protected])
2122
*/
2223

23-
#ifndef DQ_ROBOTICS_PYTHON_HEADER_GUARD
24-
#define DQ_ROBOTICS_PYTHON_HEADER_GUARD
25-
2624
#include <pybind11/pybind11.h>
2725
#include <pybind11/operators.h>
2826
#include <pybind11/stl.h>
@@ -63,6 +61,7 @@ namespace py = pybind11;
6361
#include <dqrobotics/robots/KukaYoubotRobot.h>
6462
#include <dqrobotics/robots/FrankaEmikaPandaRobot.h>
6563

64+
#include <dqrobotics/interfaces/coppeliasim/DQ_CoppeliaSimInterface.h>
6665
#include <dqrobotics/interfaces/coppeliasim/DQ_CoppeliaSimInterfaceZMQ.h>
6766

6867
#include <dqrobotics/interfaces/json11/DQ_JsonReader.h>
@@ -103,9 +102,9 @@ void init_DQ_QuadraticProgrammingController_py(py::module& m);
103102
void init_DQ_QuadraticProgrammingSolver_py(py::module& m);
104103

105104
//dqrobotics/interfaces/coppeliasim
105+
void init_DQ_CoppeliaSimInterface_py(py::module& m);
106106
void init_DQ_CoppeliaSimInterfaceZMQ_py(py::module& m);
107107

108108
//dqrobotics/interfaces/json11
109109
void init_DQ_JsonReader_py(py::module& m);
110110

111-
#endif
Lines changed: 86 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,86 @@
1+
/**
2+
(C) Copyright 2019-2025 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+
#include "../../dqrobotics_module.h"
25+
26+
void init_DQ_CoppeliaSimInterface_py(py::module& m)
27+
{
28+
/***************************************************
29+
* DQ SerialManipulator
30+
* **************************************************/
31+
py::class_<
32+
DQ_CoppeliaSimInterface,
33+
std::shared_ptr<DQ_CoppeliaSimInterface>
34+
> c(m, "DQ_SerialManipulator");
35+
36+
///Methods
37+
//Virtual
38+
//virtual bool connect(const std::string& host, const int& port, const int&TIMEOUT_IN_MILISECONDS) = 0;
39+
c.def("connect", DQ_CoppeliaSimInterface::connect,"Connects to CoppeliaSim.");
40+
//virtual void trigger_next_simulation_step() const = 0;
41+
c.def("trigger_next_simulation_step", DQ_CoppeliaSimInterface::trigger_next_simulation_step,"Triggers the next simulation step.");
42+
//virtual void set_stepping_mode(const bool& flag) const = 0;
43+
c.def("set_stepping_mode", DQ_CoppeliaSimInterface::set_stepping_mode,"Sets the stepping mode.");
44+
//virtual void start_simulation() const = 0;
45+
c.def("start_simulation", DQ_CoppeliaSimInterface::start_simulation,"Starts the simulation.");
46+
//virtual void stop_simulation() const = 0;
47+
c.def("stop_simulation", DQ_CoppeliaSimInterface::stop_simulation,"Stops the simulation.");
48+
49+
//virtual int get_object_handle(const std::string& objectname) = 0;
50+
c.def("get_object_handle", DQ_CoppeliaSimInterface::get_object_handle,"Gets the object handle.");
51+
//virtual std::vector<int> get_object_handles(const std::vector<std::string>& objectnames) = 0;
52+
c.def("get_object_handles", DQ_CoppeliaSimInterface::get_object_handles,"Gets the object handles.");
53+
54+
//virtual DQ get_object_translation(const std::string& objectname) = 0;
55+
c.def("get_object_translation", DQ_CoppeliaSimInterface::get_object_translation,"Gets the object translation.");
56+
//virtual void set_object_translation(const std::string& objectname, const DQ& t) = 0;
57+
c.def("set_object_translation", DQ_CoppeliaSimInterface::set_object_translation,"Sets the object translation.");
58+
59+
//virtual DQ get_object_rotation (const std::string& objectname) = 0;
60+
c.def("get_object_rotation", DQ_CoppeliaSimInterface::get_object_rotation,"Gets the object rotation.");
61+
//virtual void set_object_rotation (const std::string& objectname, const DQ& r) = 0;
62+
c.def("set_object_rotation", DQ_CoppeliaSimInterface::set_object_rotation,"Sets the object rotation.");
63+
64+
//virtual DQ get_object_pose (const std::string& objectname) = 0;
65+
c.def("get_object_pose", DQ_CoppeliaSimInterface::get_object_pose,"Gets the object pose.");
66+
//virtual void set_object_pose (const std::string& objectname, const DQ& h) = 0;
67+
c.def("set_object_pose", DQ_CoppeliaSimInterface::set_object_pose,"Sets the object pose.");
68+
69+
//virtual VectorXd get_joint_positions(const std::vector<std::string>& jointnames) = 0;
70+
c.def("get_joint_positions", DQ_CoppeliaSimInterface::get_joint_positions, "Gets the joint positions.");
71+
//virtual void set_joint_positions(const std::vector<std::string>& jointnames, const VectorXd& joint_positions) = 0;
72+
c.def("set_joint_positions", DQ_CoppeliaSimInterface::set_joint_positions, "Sets the joint positions.");
73+
//virtual void set_joint_target_positions(const std::vector<std::string>& jointnames, const VectorXd& joint_target_positions) = 0;
74+
c.def("set_joint_target_positions", DQ_CoppeliaSimInterface::set_joint_target_positions, "Sets the joint target positions.");
75+
76+
//virtual VectorXd get_joint_velocities(const std::vector<std::string>& jointnames) = 0;
77+
c.def("get_joint_velocities", DQ_CoppeliaSimInterface::get_joint_velocities, "Gets the joint velocities.");
78+
//virtual void set_joint_target_velocities(const std::vector<std::string>& jointnames, const VectorXd& joint_target_velocities) = 0;
79+
c.def("set_joint_target_velocities", DQ_CoppeliaSimInterface::set_joint_target_velocities, "Sets the target joint velocities");
80+
81+
//virtual void set_joint_torques(const std::vector<std::string>& jointnames, const VectorXd& torques) = 0;
82+
c.def("set_joint_torques", DQ_CoppeliaSimInterface::set_joint_torques, "Sets the joint torques");
83+
//virtual VectorXd get_joint_torques(const std::vector<std::string>& jointnames) = 0;
84+
c.def("get_joint_torques", DQ_CoppeliaSimInterface::get_joint_torques, "Gets the joint torques");
85+
86+
}

0 commit comments

Comments
 (0)