Skip to content

Adds bindings for the Link convenience class #2039

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 34 commits into from
Aug 16, 2023
Merged
Show file tree
Hide file tree
Changes from 32 commits
Commits
Show all changes
34 commits
Select commit Hold shift + click to select a range
bd9846e
Adds bindings for the world convenience class
Voldivh Jul 18, 2023
1db3735
Adds initial tests
Voldivh Jul 18, 2023
df9608e
Use alias on bindings
Voldivh Jul 19, 2023
40423f8
Adds test to this class
Voldivh Jul 25, 2023
4a013a6
Adds missing dependency for CI
Voldivh Jul 26, 2023
55e5bb7
Adds dependency to packages.apt
Voldivh Jul 26, 2023
863b61b
Adds newline at the end of file
Voldivh Jul 26, 2023
e7c955b
Renames the world sdf file
Voldivh Jul 27, 2023
cbcdf3d
Adds the rest of the test
Voldivh Aug 1, 2023
aa435d6
Removes trailing whitespace
Voldivh Aug 1, 2023
a97358d
Adds import dependency files
Voldivh Aug 8, 2023
99c9de0
Adds newline at end of files
Voldivh Aug 8, 2023
786edbf
Address reviewer feedback
mjcarroll Jul 18, 2023
4289f00
Include correct export header
mjcarroll Jul 18, 2023
5b48e80
Adds model bindings
Voldivh Jul 18, 2023
db2d815
Use alias on bindings
Voldivh Jul 19, 2023
1aeeb53
Adds test and fixes documentation
Voldivh Jul 26, 2023
4989d23
Fixes identation on sdf file
Voldivh Jul 27, 2023
af115a1
Modifies the use of import dependencies
Voldivh Aug 8, 2023
9c348d0
Adds bindings to the class
Voldivh Jul 19, 2023
eb47085
Use alias on bindings
Voldivh Jul 19, 2023
2a7f159
Adds test for the bindings
Voldivh Jul 26, 2023
9385ca7
Removes unnecessary whiteline
Voldivh Jul 26, 2023
6bd6967
Removes trailing whitespaces
Voldivh Jul 26, 2023
e8ac57a
Removes '...' from sdf file
Voldivh Aug 1, 2023
10d00fc
Modifies import dependencies
Voldivh Aug 8, 2023
a4e1556
Adds copy constructor
Voldivh Aug 10, 2023
33d5e67
Removes whitespace
Voldivh Aug 10, 2023
703ce06
Revert "Removes whitespace"
Voldivh Aug 10, 2023
057d4a9
Removes trailing whitespace
Voldivh Aug 10, 2023
d3721f0
Merge branch 'main' into voldivh/python_bindings_link
Voldivh Aug 15, 2023
c11a8fe
Modifies the use of the null entity variable
Voldivh Aug 15, 2023
5b6ba45
Modifies the amount of iteration on test
Voldivh Aug 16, 2023
cb3f6d7
Merge remote-tracking branch 'origin/main' into voldivh/python_bindin…
azeey Aug 16, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 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/Link.cc
src/gz/sim/Model.cc
src/gz/sim/TestFixture.cc
src/gz/sim/Server.cc
Expand Down Expand Up @@ -87,6 +88,7 @@ endif()

if (BUILD_TESTING)
set(python_tests
link_TEST
model_TEST
testFixture_TEST
world_TEST
Expand Down
171 changes: 171 additions & 0 deletions python/src/gz/sim/Link.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,171 @@
/*
* Copyright (C) 2023 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 "Link.hh"

namespace py = pybind11;

namespace gz
{
namespace sim
{
namespace python
{
void defineSimLink(py::object module)
{
py::class_<gz::sim::Link>(module, "Link")
.def(py::init<gz::sim::Entity>())
.def(py::init<gz::sim::Link>())
.def("entity", &gz::sim::Link::Entity,
"Get the entity which this Link is related to.")
.def("reset_entity", &gz::sim::Link::ResetEntity,
"Reset Entity to a new one.")
.def("valid", &gz::sim::Link::Valid,
py::arg("ecm"),
"Check whether this link correctly refers to an entity that "
"has a components::Link.")
.def("name", &gz::sim::Link::Name,
py::arg("ecm"),
"Get the link's unscoped name.")
.def("parent_model", &gz::sim::Link::ParentModel,
py::arg("ecm"),
"Get the parent model.")
.def("is_canonical", &gz::sim::Link::IsCanonical,
py::arg("ecm"),
"Check if this is the canonical link.")
.def("wind_mode", &gz::sim::Link::WindMode,
py::arg("ecm"),
"Get whether this link has wind enabled.")
.def("collision_by_name", &gz::sim::Link::CollisionByName,
py::arg("ecm"),
py::arg("name"),
"Get the ID of a collision entity which is an immediate child of "
"this link.")
.def("visual_by_name", &gz::sim::Link::VisualByName,
py::arg("ecm"),
py::arg("name"),
"Get the ID of a visual entity which is an immediate child of "
"this link.")
.def("collisions", &gz::sim::Link::Collisions,
py::arg("ecm"),
"Get all collisions which are immediate children of this link.")
.def("visuals", &gz::sim::Link::Visuals,
py::arg("ecm"),
"Get all visuals which are immediate children of this link.")
.def("collision_count", &gz::sim::Link::CollisionCount,
py::arg("ecm"),
"Get the number of collisions which are immediate children of "
"this link.")
.def("visual_count", &gz::sim::Link::VisualCount,
py::arg("ecm"),
"Get the number of visuals which are immediate children of this "
"link.")
.def("world_pose", &gz::sim::Link::WorldPose,
py::arg("ecm"),
"Get the pose of the link frame in the world coordinate frame.")
.def("world_inertial_pose", &gz::sim::Link::WorldInertialPose,
py::arg("ecm"),
"Get the world pose of the link inertia.")
.def("world_linear_velocity",
py::overload_cast<const EntityComponentManager &>(&gz::sim::Link::WorldLinearVelocity, py::const_),
py::arg("ecm"),
"Get the linear velocity at the origin of of the link frame "
"expressed in the world frame, using an offset expressed in a "
"body-fixed frame. If no offset is given, the velocity at the origin of "
"the Link frame will be returned.")
.def("world_linear_velocity",
py::overload_cast<const EntityComponentManager &, const math::Vector3d &>(&gz::sim::Link::WorldLinearVelocity, py::const_),
py::arg("ecm"),
py::arg("offset"),
"Get the linear velocity of a point on the body in the world "
"frame, using an offset expressed in a body-fixed frame.")
.def("world_angular_velocity", &gz::sim::Link::WorldAngularVelocity,
py::arg("ecm"),
"Get the angular velocity of the link in the world frame.")
.def("enable_velocity_checks", &gz::sim::Link::EnableVelocityChecks,
py::arg("ecm"),
py::arg("enable") = true,
"By default, Gazebo will not report velocities for a link, so "
"functions like `world_linear_velocity` will return nullopt. This "
"function can be used to enable all velocity checks.")
.def("set_linear_velocity", &gz::sim::Link::SetLinearVelocity,
py::arg("ecm"),
py::arg("velocity"),
"Set the linear velocity on this link. If this is set, wrenches "
"on this link will be ignored for the current time step.")
.def("set_angular_velocity", &gz::sim::Link::SetAngularVelocity,
py::arg("ecm"),
py::arg("velocity"),
"Set the angular velocity on this link. If this is set, wrenches "
"on this link will be ignored for the current time step.")
.def("world_angular_acceleration", &gz::sim::Link::WorldAngularAcceleration,
py::arg("ecm"),
"Get the linear acceleration of the body in the world frame.")
.def("world_linear_acceleration", &gz::sim::Link::WorldLinearAcceleration,
py::arg("ecm"),
"Get the angular velocity of the link in the world frame.")
.def("enable_acceleration_checks", &gz::sim::Link::EnableAccelerationChecks,
py::arg("ecm"),
py::arg("enable") = true,
"By default, Gazebo will not report accelerations for a link, so "
"functions like `world_linear_acceleration` will return nullopt. This "
"function can be used to enable all acceleration checks.")
.def("world_inertia_matrix", &gz::sim::Link::WorldInertiaMatrix,
py::arg("ecm"),
"Get the inertia matrix in the world frame.")
.def("world_kinetic_energy", &gz::sim::Link::WorldKineticEnergy,
py::arg("ecm"),
"Get the rotational and translational kinetic energy of the "
"link with respect to the world frame.")
.def("add_world_force",
py::overload_cast<EntityComponentManager &, const math::Vector3d &>(&gz::sim::Link::AddWorldForce, py::const_),
py::arg("ecm"),
py::arg("force"),
"Add a force expressed in world coordinates and applied at the "
"center of mass of the link.")
.def("add_world_force",
py::overload_cast<EntityComponentManager &, const math::Vector3d &, const math::Vector3d &>(&gz::sim::Link::AddWorldForce, py::const_),
py::arg("ecm"),
py::arg("force"),
py::arg("position"),
"Add a force expressed in world coordinates and applied at "
"an offset from the center of mass of the link.")
.def("add_world_wrench", &gz::sim::Link::AddWorldWrench,
py::arg("ecm"),
py::arg("force"),
py::arg("torque"),
"Add a wrench expressed in world coordinates and applied to "
"the link at the link's origin. This wrench is applied for one "
"simulation step.")
.def("__copy__",
[](const gz::sim::Link &self)
{
return gz::sim::Link(self);
})
.def("__deepcopy__",
[](const gz::sim::Link &self, pybind11::dict)
{
return gz::sim::Link(self);
});
}
} // namespace python
} // namespace sim
} // namespace gz
40 changes: 40 additions & 0 deletions python/src/gz/sim/Link.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/*
* Copyright (C) 2023 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__LINK_HH_
#define GZ_SIM_PYTHON__LINK_HH_

#include <pybind11/pybind11.h>

#include <gz/sim/Link.hh>

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

#endif // GZ_SIM_PYTHON__Link_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 @@ -20,6 +20,7 @@

#include "EntityComponentManager.hh"
#include "EventManager.hh"
#include "Link.hh"
#include "Model.hh"
#include "Server.hh"
#include "ServerConfig.hh"
Expand All @@ -33,6 +34,7 @@ PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) {
m.attr("K_NULL_ENTITY") = gz::sim::kNullEntity;
gz::sim::python::defineSimEntityComponentManager(m);
gz::sim::python::defineSimEventManager(m);
gz::sim::python::defineSimLink(m);
gz::sim::python::defineSimModel(m);
gz::sim::python::defineSimServer(m);
gz::sim::python::defineSimServerConfig(m);
Expand Down
103 changes: 103 additions & 0 deletions python/test/link_TEST.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,103 @@
#!/usr/bin/env python3
# Copyright (C) 2023 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.

import os
import unittest

from gz.common import set_verbosity
from gz_test_deps.sim import K_NULL_ENTITY, TestFixture, Link, Model, World, world_entity
from gz_test_deps.math import Matrix3d, Vector3d

class TestModel(unittest.TestCase):
post_iterations = 0
iterations = 0
pre_iterations = 0

def test_model(self):
set_verbosity(4)

file_path = os.path.dirname(os.path.realpath(__file__))
fixture = TestFixture(os.path.join(file_path, 'link_test.sdf'))

def on_post_udpate_cb(_info, _ecm):
self.post_iterations += 1

def on_pre_udpate_cb(_info, _ecm):
self.pre_iterations += 1
world_e = world_entity(_ecm)
self.assertNotEqual(K_NULL_ENTITY, world_e)
w = World(world_e)
m = Model(w.model_by_name(_ecm, 'model_test'))
link = Link(m.link_by_name(_ecm, 'link_test'))
# Entity Test
self.assertNotEqual(K_NULL_ENTITY, link.entity())
# Valid Test
self.assertTrue(link.valid(_ecm))
# Name Test
self.assertEqual('link_test', link.name(_ecm))
# Parent Model Test
self.assertEqual(m.entity(), link.parent_model(_ecm).entity())
# Canonical test
self.assertTrue(link.is_canonical(_ecm))
# Wind Mode test
self.assertTrue(link.wind_mode(_ecm))
# Collisions Test
self.assertNotEqual(K_NULL_ENTITY, link.collision_by_name(_ecm, 'collision_test'))
self.assertEqual(1, link.collision_count(_ecm))
# Visuals Test
self.assertNotEqual(K_NULL_ENTITY, link.visual_by_name(_ecm, 'visual_test'))
self.assertEqual(1, link.visual_count(_ecm))
# World Pose Test
self.assertEqual(None, link.world_pose(_ecm))
self.assertEqual(None, link.world_inertial_pose(_ecm))
# World Velocity Test
self.assertEqual(None, link.world_linear_velocity(_ecm))
self.assertEqual(None, link.world_angular_velocity(_ecm))
link.enable_velocity_checks(_ecm, True)
link.set_linear_velocity(_ecm, Vector3d())
link.set_angular_velocity(_ecm, Vector3d())
self.assertEqual(Vector3d(), link.world_linear_velocity(_ecm))
self.assertEqual(Vector3d(), link.world_angular_velocity(_ecm))
# World Acceleration Test
self.assertEqual(None, link.world_linear_acceleration(_ecm))
self.assertEqual(None, link.world_angular_acceleration(_ecm))
link.enable_acceleration_checks(_ecm, True)
self.assertEqual(Vector3d(), link.world_linear_acceleration(_ecm))
self.assertEqual(Vector3d(), link.world_angular_acceleration(_ecm))
# World Inertia Matrix Test
self.assertEqual(Matrix3d(1,0,0,0,1,0,0,0,1), link.world_inertia_matrix(_ecm))
# World Kinetic Energy Test
self.assertEqual(0, link.world_kinetic_energy(_ecm))
link.enable_velocity_checks(_ecm, False)
link.enable_acceleration_checks(_ecm, False)


def on_udpate_cb(_info, _ecm):
self.iterations += 1

fixture.on_post_update(on_post_udpate_cb)
fixture.on_update(on_udpate_cb)
fixture.on_pre_update(on_pre_udpate_cb)
fixture.finalize()

server = fixture.server()
server.run(True, 1000, False)

self.assertEqual(1000, self.pre_iterations)
self.assertEqual(1000, self.iterations)
self.assertEqual(1000, self.post_iterations)

if __name__ == '__main__':
unittest.main()
45 changes: 45 additions & 0 deletions python/test/link_test.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="world_test">
<model name="model_test">
<link name="link_test">
<pose>0 0 0 0 0 0</pose>
<enable_wind>true</enable_wind>
<inertial>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>10.0</mass>
</inertial>

<collision name="collision_test">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>

<visual name="visual_test">
<pose>0 0 1 0 0 0</pose>
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</visual>

<sensor type="camera" name="my_sensor">
</sensor>

</link>

</model>
</world>
</sdf>