Skip to content

Commit 4abe5f7

Browse files
author
Murilo M. Marinho
committed
[CMakeLists.txt] Add DQ_CoppeliaSim wrapper to CMAKE and fix reference to methods.
1 parent 3fdebcc commit 4abe5f7

File tree

2 files changed

+21
-20
lines changed

2 files changed

+21
-20
lines changed

CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,7 @@ pybind11_add_module(_dqrobotics
9595
interfaces/cpp-interface-json11/dropbox/json11/json11.cpp
9696

9797
#interfaces/copppeliasim-zmq
98+
src/interfaces/coppeliasim/DQ_CoppeliaSimInterface_py.cpp
9899
src/interfaces/coppeliasim/DQ_CoppeliaSimInterfaceZMQ_py.cpp
99100
)
100101

src/interfaces/coppeliasim/DQ_CoppeliaSimInterface_py.cpp

Lines changed: 20 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -36,51 +36,51 @@ void init_DQ_CoppeliaSimInterface_py(py::module& m)
3636
///Methods
3737
//Virtual
3838
//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.");
39+
c.def("connect", &DQ_CoppeliaSimInterface::connect,"Connects to CoppeliaSim.");
4040
//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.");
41+
c.def("trigger_next_simulation_step", &DQ_CoppeliaSimInterface::trigger_next_simulation_step,"Triggers the next simulation step.");
4242
//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.");
43+
c.def("set_stepping_mode", &DQ_CoppeliaSimInterface::set_stepping_mode,"Sets the stepping mode.");
4444
//virtual void start_simulation() const = 0;
45-
c.def("start_simulation", DQ_CoppeliaSimInterface::start_simulation,"Starts the simulation.");
45+
c.def("start_simulation", &DQ_CoppeliaSimInterface::start_simulation,"Starts the simulation.");
4646
//virtual void stop_simulation() const = 0;
47-
c.def("stop_simulation", DQ_CoppeliaSimInterface::stop_simulation,"Stops the simulation.");
47+
c.def("stop_simulation", &DQ_CoppeliaSimInterface::stop_simulation,"Stops the simulation.");
4848

4949
//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.");
50+
c.def("get_object_handle", &DQ_CoppeliaSimInterface::get_object_handle,"Gets the object handle.");
5151
//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.");
52+
c.def("get_object_handles", &DQ_CoppeliaSimInterface::get_object_handles,"Gets the object handles.");
5353

5454
//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.");
55+
c.def("get_object_translation", &DQ_CoppeliaSimInterface::get_object_translation,"Gets the object translation.");
5656
//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.");
57+
c.def("set_object_translation", &DQ_CoppeliaSimInterface::set_object_translation,"Sets the object translation.");
5858

5959
//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.");
60+
c.def("get_object_rotation", &DQ_CoppeliaSimInterface::get_object_rotation,"Gets the object rotation.");
6161
//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.");
62+
c.def("set_object_rotation", &DQ_CoppeliaSimInterface::set_object_rotation,"Sets the object rotation.");
6363

6464
//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.");
65+
c.def("get_object_pose", &DQ_CoppeliaSimInterface::get_object_pose,"Gets the object pose.");
6666
//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.");
67+
c.def("set_object_pose", &DQ_CoppeliaSimInterface::set_object_pose,"Sets the object pose.");
6868

6969
//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.");
70+
c.def("get_joint_positions", &DQ_CoppeliaSimInterface::get_joint_positions, "Gets the joint positions.");
7171
//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.");
72+
c.def("set_joint_positions", &DQ_CoppeliaSimInterface::set_joint_positions, "Sets the joint positions.");
7373
//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.");
74+
c.def("set_joint_target_positions", &DQ_CoppeliaSimInterface::set_joint_target_positions, "Sets the joint target positions.");
7575

7676
//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.");
77+
c.def("get_joint_velocities", &DQ_CoppeliaSimInterface::get_joint_velocities, "Gets the joint velocities.");
7878
//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");
79+
c.def("set_joint_target_velocities", &DQ_CoppeliaSimInterface::set_joint_target_velocities, "Sets the target joint velocities");
8080

8181
//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");
82+
c.def("set_joint_torques", &DQ_CoppeliaSimInterface::set_joint_torques, "Sets the joint torques");
8383
//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");
84+
c.def("get_joint_torques", &DQ_CoppeliaSimInterface::get_joint_torques, "Gets the joint torques");
8585

8686
}

0 commit comments

Comments
 (0)