Skip to content

Commit

Permalink
Adds the bindings for the joint class
Browse files Browse the repository at this point in the history
Signed-off-by: Voldivh <eloyabmfcv@gmail.com>
  • Loading branch information
Voldivh committed Jul 26, 2023
1 parent 30439ab commit 4b414fd
Show file tree
Hide file tree
Showing 5 changed files with 185 additions and 1 deletion.
2 changes: 1 addition & 1 deletion include/gz/sim/Joint.hh
Original file line number Diff line number Diff line change
Expand Up @@ -260,7 +260,7 @@ namespace gz
public: std::optional<std::vector<double>> Position(
const EntityComponentManager &_ecm) const;

/// \brief Get the position of the joint
/// \brief Get the transmitted wrench of the joint
/// \param[in] _ecm Entity-component manager.
/// \return Transmitted wrench of the joint or nullopt if transmitted
/// wrench check is not enabled.
Expand Down
1 change: 1 addition & 0 deletions python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ pybind11_add_module(${BINDINGS_MODULE_NAME} MODULE
src/gz/sim/_gz_sim_pybind11.cc
src/gz/sim/EntityComponentManager.cc
src/gz/sim/EventManager.cc
src/gz/sim/Joint.cc
src/gz/sim/Model.cc
src/gz/sim/TestFixture.cc
src/gz/sim/Server.cc
Expand Down
141 changes: 141 additions & 0 deletions python/src/gz/sim/Joint.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,141 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/


#include <pybind11/pybind11.h>
#include <pybind11/stl.h>

#include <iostream>

#include "Joint.hh"

namespace py = pybind11;

namespace gz
{
namespace sim
{
namespace python
{
void defineSimJoint(py::object module)
{
py::class_<gz::sim::Joint>(module, "Joint")
.def(py::init<gz::sim::Entity>())
.def("entity", &gz::sim::Joint::Entity,
"Get the entity which this Joint is related to.")
.def("reset_entity", &gz::sim::Joint::ResetEntity,
py::arg("new_entity"),
"Reset Entity to a new one.")
.def("valid", &gz::sim::Joint::Valid,
py::arg("ecm"),
"Check whether this joint correctly refers to an entity that"
"has a components::Joint.")
.def("name", &gz::sim::Joint::Name,
py::arg("ecm"),
"Get the joint's unscoped name.")
.def("parent_link_name", &gz::sim::Joint::ParentLinkName,
py::arg("ecm"),
"Get the parent link name.")
.def("child_link_name", &gz::sim::Joint::ChildLinkName,
py::arg("ecm"),
"Get the child link name.")
.def("pose", &gz::sim::Joint::Pose,
py::arg("ecm"),
"Get the pose of the joint.")
.def("thread_pitch", &gz::sim::Joint::ThreadPitch,
py::arg("ecm"),
"Get the thread pitch of the joint.")
.def("axis", &gz::sim::Joint::Axis,
py::arg("ecm"),
"Get the joint axis.")
.def("type", &gz::sim::Joint::Type,
py::arg("ecm"),
"Get the joint type.")
.def("sensor_by_name", &gz::sim::Joint::SensorByName,
py::arg("ecm"),
py::arg("name"),
"Get the ID of a sensor entity which is an immediate child of"
"this joint.")
.def("sensors", &gz::sim::Joint::Sensors,
py::arg("ecm"),
"Get all sensors which are immediate children of this joint.")
.def("sensor_count", &gz::sim::Joint::SensorCount,
py::arg("ecm"),
"Get the number of sensors which are immediate children of this"
"joint.")
.def("set_velocity", &gz::sim::Joint::SetVelocity,
py::arg("ecm"),
py::arg("velocities"),
"Set velocity on this joint. Only applied if no forces are set.")
.def("set_force", &gz::sim::Joint::SetForce,
py::arg("ecm"),
py::arg("forces"),
"Set force on this joint. If both forces and velocities are set,"
"only forces are applied.")
.def("set_velocity_limits", &gz::sim::Joint::SetVelocityLimits,
py::arg("ecm"),
py::arg("limits"),
"Set the velocity limits on a joint axis.")
.def("set_effort_limits", &gz::sim::Joint::SetEffortLimits,
py::arg("ecm"),
py::arg("limits"),
"Set the effort limits on a joint axis.")
.def("set_position_imits", &gz::sim::Joint::SetPositionLimits,
py::arg("ecm"),
py::arg("limits"),
"Set the position limits on a joint axis.")
.def("reset_position", &gz::sim::Joint::ResetPosition,
py::arg("ecm"),
py::arg("positions"),
"Reset the joint positions.")
.def("reset_velocity", &gz::sim::Joint::ResetVelocity,
py::arg("ecm"),
py::arg("velocities"),
"Reset the joint velocities.")
.def("enable_velocity_check", &gz::sim::Joint::EnableVelocityCheck,
py::arg("ecm"),
py::arg("enable") = true,
"By default, Gazebo will not report velocities for a joint, so"
"functions like `Velocity` will return nullopt. This"
"function can be used to enable joint velocity check.")
.def("enable_position_check", &gz::sim::Joint::EnablePositionCheck,
py::arg("ecm"),
py::arg("enable") = true,
"By default, Gazebo will not report positions for a joint, so"
"functions like `Position` will return nullopt. This"
"function can be used to enable joint position check.")
.def("enable_transmitted_wrench_check", &gz::sim::Joint::EnableTransmittedWrenchCheck,
py::arg("ecm"),
py::arg("enable") = true,
"By default, Gazebo will not report transmitted wrench for a"
"joint, so functions like `TransmittedWrench` will return nullopt. This"
"function can be used to enable joint transmitted wrench check.")
.def("velocity", &gz::sim::Joint::Velocity,
py::arg("ecm"),
"Get the velocity of the joint.")
.def("position", &gz::sim::Joint::Position,
py::arg("ecm"),
"Get the position of the joint.")
.def("transmitted_wrench", &gz::sim::Joint::TransmittedWrench,
py::arg("ecm"),
"Get the transmitted wrench of the joint.")
.def("parent_model", &gz::sim::Joint::ParentModel,
py::arg("ecm"),
"Get the parent model of the joint.");
}
} // namespace python
} // namespace sim
} // namespace gz
40 changes: 40 additions & 0 deletions python/src/gz/sim/Joint.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/

#ifndef GZ_SIM_PYTHON__JOINT_HH_
#define GZ_SIM_PYTHON__JOINT_HH_

#include <pybind11/pybind11.h>

#include <gz/sim/Joint.hh>

namespace gz
{
namespace sim
{
namespace python
{
/// Define a pybind11 wrapper for a gz::sim::Joint
/**
* \param[in] module a pybind11 module to add the definition to
*/
void
defineSimJoint(pybind11::object module);
} // namespace python
} // namespace sim
} // namespace gz

#endif // GZ_SIM_PYTHON__JOINT_HH_
2 changes: 2 additions & 0 deletions python/src/gz/sim/_gz_sim_pybind11.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

#include "EntityComponentManager.hh"
#include "EventManager.hh"
#include "Joint.hh"
#include "Model.hh"
#include "Server.hh"
#include "ServerConfig.hh"
Expand All @@ -31,6 +32,7 @@ PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) {

gz::sim::python::defineSimEntityComponentManager(m);
gz::sim::python::defineSimEventManager(m);
gz::sim::python::defineSimJoint(m);
gz::sim::python::defineSimModel(m);
gz::sim::python::defineSimServer(m);
gz::sim::python::defineSimServerConfig(m);
Expand Down

0 comments on commit 4b414fd

Please sign in to comment.