Skip to content
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

Clean-up to simplify API for GUI/Sensor #113

Merged
merged 5 commits into from
Oct 12, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
6 changes: 3 additions & 3 deletions cmake/example/example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
#endif

struct StateDesc : public robot_dart::descriptor::BaseDescriptor {
StateDesc(robot_dart::RobotDARTSimu* simu, size_t desc_dump = 1) : robot_dart::descriptor::BaseDescriptor(simu, desc_dump) {}
StateDesc(size_t desc_dump = 1) : robot_dart::descriptor::BaseDescriptor(desc_dump) {}

void operator()()
{
Expand Down Expand Up @@ -42,9 +42,9 @@ int main()

robot_dart::RobotDARTSimu simu;
#ifdef GRAPHIC
simu.set_graphics(std::make_shared<robot_dart::gui::magnum::Graphics>(&simu));
simu.set_graphics(std::make_shared<robot_dart::gui::magnum::Graphics>());
#endif
simu.add_descriptor(std::make_shared<StateDesc>(&simu));
simu.add_descriptor(std::make_shared<StateDesc>());
simu.add_robot(g_robot);
std::cout << (g_robot->body_pose("arm_link_5") * size).transpose() << std::endl;
simu.run(2.5);
Expand Down
6 changes: 3 additions & 3 deletions src/examples/arm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
#endif

struct StateDesc : public robot_dart::descriptor::BaseDescriptor {
StateDesc(robot_dart::RobotDARTSimu* simu, size_t desc_dump = 1) : robot_dart::descriptor::BaseDescriptor(simu, desc_dump) {}
StateDesc(size_t desc_dump = 1) : robot_dart::descriptor::BaseDescriptor(desc_dump) {}

void operator()()
{
Expand Down Expand Up @@ -42,9 +42,9 @@ int main()

robot_dart::RobotDARTSimu simu;
#ifdef GRAPHIC
simu.set_graphics(std::make_shared<robot_dart::gui::magnum::Graphics>(&simu));
simu.set_graphics(std::make_shared<robot_dart::gui::magnum::Graphics>());
#endif
simu.add_descriptor(std::make_shared<StateDesc>(&simu));
simu.add_descriptor(std::make_shared<StateDesc>());
simu.add_robot(g_robot);
std::cout << (g_robot->body_pose("arm_link_5") * size).transpose() << std::endl;
simu.run(2.5);
Expand Down
4 changes: 2 additions & 2 deletions src/examples/cameras.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ int main()
robot_dart::gui::magnum::GraphicsConfiguration configuration;
configuration.width = 1024;
configuration.height = 768;
auto graphics = std::make_shared<robot_dart::gui::magnum::BaseGraphics<MyApp>>(&simu, configuration);
auto graphics = std::make_shared<robot_dart::gui::magnum::BaseGraphics<MyApp>>(configuration);
simu.set_graphics(graphics);
graphics->look_at({0., 3.5, 2.}, {0., 0., 0.25});

Expand All @@ -61,7 +61,7 @@ int main()
graphics->record_video("video-main.mp4", simu.graphics_freq());

// Add camera
auto camera = std::make_shared<robot_dart::sensor::Camera>(&simu, graphics->magnum_app(), 256, 256);
auto camera = std::make_shared<robot_dart::sensor::Camera>(graphics->magnum_app(), 256, 256);
camera->camera().set_far_plane(5.f);
camera->camera().record(true, true); // cameras are recording color images by default, enable depth images as well for this example
// cameras can also record video
Expand Down
2 changes: 1 addition & 1 deletion src/examples/control_loop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ int main()

robot_dart::RobotDARTSimu simu(1e-3);
#ifdef GRAPHIC
simu.set_graphics(std::make_shared<robot_dart::gui::magnum::Graphics>(&simu));
simu.set_graphics(std::make_shared<robot_dart::gui::magnum::Graphics>());
#endif

simu.add_robot(robot);
Expand Down
2 changes: 1 addition & 1 deletion src/examples/dof_maps.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ int main()
float dt = 0.001;
robot_dart::RobotDARTSimu simu(dt);
#ifdef GRAPHIC
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>(&simu);
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>();
simu.set_graphics(graphics);
graphics->look_at({0., 3.5, 2.}, {0., 0., 0.25});
#endif
Expand Down
2 changes: 1 addition & 1 deletion src/examples/hexapod.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ int main()

robot_dart::RobotDARTSimu simu(0.001);
#ifdef GRAPHIC
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>(&simu);
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>();
simu.set_graphics(graphics);
graphics->look_at({0.5, 3., 0.75}, {0.5, 0., 0.2});
#endif
Expand Down
6 changes: 3 additions & 3 deletions src/examples/icub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ int main()
robot_dart::RobotDARTSimu simu(0.001);
simu.set_collision_detector("fcl");
#ifdef GRAPHIC
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>(&simu);
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>();
simu.set_graphics(graphics);
graphics->look_at({0., 3.5, 2.}, {0., 0., 0.25});
// graphics->record_video("icub.mp4");
Expand All @@ -47,10 +47,10 @@ int main()
robot_dart::sensor::IMUConfig imu_config;
imu_config.body = robot->body_node("chest"); // choose which body the sensor is attached to
imu_config.frequency = 200; // update rate of the sensor
auto imu_sensor = simu.add_sensor<robot_dart::sensor::IMU>(&simu, imu_config);
auto imu_sensor = simu.add_sensor<robot_dart::sensor::IMU>(imu_config);

// Add a force/torque sensor in "r_ankle_roll" joint
auto ft_sensor = simu.add_sensor<robot_dart::sensor::ForceTorque>(&simu, robot, "r_ankle_roll");
auto ft_sensor = simu.add_sensor<robot_dart::sensor::ForceTorque>(robot, "r_ankle_roll");

// Add some visualizations
robot->set_draw_axis(imu_config.body->getName());
Expand Down
2 changes: 1 addition & 1 deletion src/examples/iiwa.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ int main()
robot_dart::RobotDARTSimu simu(0.001);
simu.set_collision_detector("fcl");
#ifdef GRAPHIC
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>(&simu);
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>();
simu.set_graphics(graphics);

graphics->look_at({0., 3.5, 2.}, {0., 0., 0.25});
Expand Down
2 changes: 1 addition & 1 deletion src/examples/magnum_contexts.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ int main()
robot_dart::gui::magnum::GraphicsConfiguration configuration;
configuration.width = 1024;
configuration.height = 768;
auto graphics = std::make_shared<robot_dart::gui::magnum::WindowlessGraphics>(&simu, configuration);
auto graphics = std::make_shared<robot_dart::gui::magnum::WindowlessGraphics>(configuration);
simu.set_graphics(graphics);
// Position the camera differently for each thread to visualize the difference
graphics->look_at({0.4 * index, 3.5 - index * 0.1, 2.}, {0., 0., 0.25});
Expand Down
4 changes: 2 additions & 2 deletions src/examples/pendulum.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
#endif

struct StateDesc : public robot_dart::descriptor::BaseDescriptor {
StateDesc(robot_dart::RobotDARTSimu* simu, size_t desc_dump = 1) : robot_dart::descriptor::BaseDescriptor(simu, desc_dump) {}
StateDesc(size_t desc_dump = 1) : robot_dart::descriptor::BaseDescriptor(desc_dump) {}

void operator()()
{
Expand Down Expand Up @@ -53,7 +53,7 @@ int main()

robot_dart::RobotDARTSimu simu;
#ifdef GRAPHIC
simu.set_graphics(std::make_shared<robot_dart::gui::magnum::Graphics>(&simu));
simu.set_graphics(std::make_shared<robot_dart::gui::magnum::Graphics>());
#endif
// <Type>(desc_period)
simu.add_descriptor<StateDesc>(2);
Expand Down
2 changes: 1 addition & 1 deletion src/examples/talos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ int main()
robot_dart::RobotDARTSimu simu(dt);
simu.set_collision_detector("fcl");
#ifdef GRAPHIC
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>(&simu);
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>();
simu.set_graphics(graphics);
graphics->look_at({0., 3.5, 2.}, {0., 0., 0.25});
graphics->record_video("talos_dancing.mp4");
Expand Down
2 changes: 1 addition & 1 deletion src/examples/talos_fast.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ int main()
// we use dart, but only the feet are used
simu.set_collision_detector("dart");
#ifdef GRAPHIC
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>(&simu);
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>();
simu.set_graphics(graphics);
graphics->look_at({0., 3.5, 2.}, {0., 0., 0.25});
graphics->record_video("talos.mp4");
Expand Down
2 changes: 1 addition & 1 deletion src/examples/transparent.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ int main()
// choose time step of 0.001 seconds
robot_dart::RobotDARTSimu simu(0.001);
#ifdef GRAPHIC
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>(&simu);
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>();
simu.set_graphics(graphics);
// set the camera at position (0, 3, 1) looking at the center (0, 0, 0)
graphics->look_at({0., 3., 1.}, {0., 0., 0.});
Expand Down
2 changes: 1 addition & 1 deletion src/examples/tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ int main()
// choose time step of 0.001 seconds
robot_dart::RobotDARTSimu simu(0.001);
#ifdef GRAPHIC
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>(&simu);
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>();
simu.set_graphics(graphics);
// set the camera at position (0, 3, 1) looking at the center (0, 0, 0)
graphics->look_at({0., 3., 1.}, {0., 0., 0.});
Expand Down
12 changes: 6 additions & 6 deletions src/python/example.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@ def clone(self):
return MyController(self._ctrl, self._controllable_dofs)

class MyDesc(rd.Descriptor):
def __init__(self, simu, desc):
rd.Descriptor.__init__(self, simu, desc)
def __init__(self, desc):
rd.Descriptor.__init__(self, desc)
self._states = []

def __call__(self):
Expand All @@ -45,23 +45,23 @@ def __call__(self):

# Create simulator object
simu = rd.RobotDARTSimu(0.001)
desc = MyDesc(simu, 10)
desc = MyDesc(10)
simu.add_descriptor(desc)

# Create graphics
graphics = rd.gui.Graphics(simu, rd.gui.GraphicsConfiguration())
graphics = rd.gui.Graphics()
simu.set_graphics(graphics)
# graphics.clear_lights()
# mat = rd.gui.Material(magnum.Color4(0, 0, 0, 1), magnum.Color4(1, 1, 1, 1), magnum.Color4(1, 1, 1, 1), 80.)
# graphics.add_light(rd.gui.create_point_light(magnum.Vector3(-1., 1., 2.), mat, 2., magnum.Vector3(0., 0., 1.)))
# graphics.add_light(rd.gui.create_point_light(magnum.Vector3(1., -1., 2.), mat, 2., magnum.Vector3(0., 0., 1.)))
simu.set_graphics(graphics)

# Add robot and floor to the simulation
simu.add_robot(robot)
simu.add_checkerboard_floor(10., 0.1, 1., np.zeros((6,1)), "floor")

# Add a camera sensor to the end-effector of the manipulator
camera = rd.sensor.Camera(simu, graphics.magnum_app(), 256, 256)
camera = rd.sensor.Camera(graphics.magnum_app(), 256, 256)
rot = dartpy.math.AngleAxis(3.14, [1., 0., 0.]).to_rotation_matrix()
rot = rot.dot(dartpy.math.AngleAxis(1.57, [0., 0., 1.]).to_rotation_matrix())
camera.attach_to_body(robot.body_node("arm_link_5"), dartpy.math.Isometry3(rotation=rot, translation=[0., 0., 0.1]))
Expand Down
5 changes: 3 additions & 2 deletions src/python/example_parallel.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,11 @@ def test():
simu = rd.RobotDARTSimu(0.001)

# set the graphics
graphics = rd.gui.WindowlessGraphics(simu, rd.gui.GraphicsConfiguration())
graphics.look_at([0.4 * ii, 3.5 - ii * 0.1, 2.], [0., 0., 0.25], [0., 0., 1.])
graphics = rd.gui.WindowlessGraphics()
simu.set_graphics(graphics)

graphics.look_at([0.4 * ii, 3.5 - ii * 0.1, 2.], [0., 0., 0.25], [0., 0., 1.])

# add the robot and the floor
simu.add_robot(grobot)
simu.add_checkerboard_floor(10., 0.1, 1., np.zeros((6,1)), "floor")
Expand Down
12 changes: 8 additions & 4 deletions src/python/gui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,13 +115,17 @@ namespace robot_dart {
using namespace robot_dart::gui::magnum;
// Graphics class
py::class_<Graphics, BaseWindowedGraphics, std::shared_ptr<Graphics>>(sm, "Graphics")
.def(py::init<RobotDARTSimu*, const GraphicsConfiguration&>())
.def(py::init<const GraphicsConfiguration&>(),
py::arg("configuration") = GraphicsConfiguration())

.def("done", &Graphics::done)
.def("refresh", &Graphics::refresh)
.def("set_render_period", &Graphics::set_render_period)
.def("set_enable", &Graphics::set_enable)

.def("set_simu", &Graphics::set_simu)
.def("simu", &Graphics::simu, py::return_value_policy::reference)

.def("look_at", &Graphics::look_at,
py::arg("camera_pos"),
py::arg("look_at") = Eigen::Vector3d(0, 0, 0),
Expand Down Expand Up @@ -157,7 +161,8 @@ namespace robot_dart {

// WindowlessGraphics class
py::class_<WindowlessGraphics, BaseWindowlessGraphics, std::shared_ptr<WindowlessGraphics>>(sm, "WindowlessGraphics")
.def(py::init<RobotDARTSimu*, const GraphicsConfiguration&>())
.def(py::init<const GraphicsConfiguration&>(),
py::arg("configuration") = GraphicsConfiguration())

.def("done", &WindowlessGraphics::done)
.def("refresh", &WindowlessGraphics::refresh)
Expand Down Expand Up @@ -214,8 +219,7 @@ namespace robot_dart {

// Camera sensor class
py::class_<gui::magnum::sensor::Camera, robot_dart::sensor::Sensor, std::shared_ptr<gui::magnum::sensor::Camera>>(sensormodule, "Camera")
.def(py::init<RobotDARTSimu*, gui::magnum::BaseApplication*, size_t, size_t, size_t, bool>(),
py::arg("simu"),
.def(py::init<gui::magnum::BaseApplication*, size_t, size_t, size_t, bool>(),
py::arg("app"),
py::arg("width"),
py::arg("height"),
Expand Down
15 changes: 7 additions & 8 deletions src/python/sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,8 +102,7 @@ namespace robot_dart {
};

py::class_<Sensor, PySensor, std::shared_ptr<Sensor>>(sensormodule, "Sensor")
.def(py::init<RobotDARTSimu*, size_t>(),
py::arg("simu"),
.def(py::init<size_t>(),
py::arg("freq") = 40)

.def_readwrite("_active", &PublicistSensor::_active)
Expand All @@ -122,6 +121,9 @@ namespace robot_dart {
py::arg("enable") = true)
.def("active", &Sensor::active)

.def("set_simu", &Sensor::set_simu)
.def("simu", &Sensor::simu, py::return_value_policy::reference)

.def("frequency", &Sensor::frequency)
.def("set_frequency", &Sensor::set_frequency,
py::arg("freq"))
Expand Down Expand Up @@ -166,13 +168,11 @@ namespace robot_dart {
};

py::class_<sensor::ForceTorque, Sensor, std::shared_ptr<sensor::ForceTorque>>(sensormodule, "ForceTorque")
.def(py::init<RobotDARTSimu*, dart::dynamics::Joint*, size_t, const std::string&>(),
py::arg("simu"),
.def(py::init<dart::dynamics::Joint*, size_t, const std::string&>(),
py::arg("joint"),
py::arg("frequency") = 1000,
py::arg("direction") = "child_to_parent")
.def(py::init<RobotDARTSimu*, const std::shared_ptr<Robot>&, const std::string&, size_t, const std::string&>(),
py::arg("simu"),
.def(py::init<const std::shared_ptr<Robot>&, const std::string&, size_t, const std::string&>(),
py::arg("robot"),
py::arg("joint_name"),
py::arg("frequency") = 1000,
Expand Down Expand Up @@ -216,8 +216,7 @@ namespace robot_dart {
};

py::class_<sensor::IMU, Sensor, std::shared_ptr<sensor::IMU>>(sensormodule, "IMU")
.def(py::init<RobotDARTSimu*, const sensor::IMUConfig&>(),
py::arg("simu"),
.def(py::init<const sensor::IMUConfig&>(),
py::arg("config"))

.def_readonly("_config", &PublicistIMUSensor::_config)
Expand Down
3 changes: 2 additions & 1 deletion src/python/simu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,8 @@ namespace robot_dart {
};

py::class_<Descriptor, PyDescriptor, std::shared_ptr<Descriptor>>(m, "Descriptor")
.def(py::init<RobotDARTSimu*, size_t>())
.def(py::init<size_t>(),
py::arg("desc_dump") = 1)

.def_readwrite("_desc_period", &PublicistDescriptor::_desc_period)
.def_readonly("_simu", &PublicistDescriptor::_simu)
Expand Down
2 changes: 1 addition & 1 deletion src/robot_dart/descriptor/base_descriptor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

namespace robot_dart {
namespace descriptor {
BaseDescriptor::BaseDescriptor(RobotDARTSimu* simu, size_t desc_dump) : _simu(simu), _desc_period(desc_dump) {}
BaseDescriptor::BaseDescriptor(size_t desc_dump) : _desc_period(desc_dump) {}

size_t BaseDescriptor::desc_dump() const
{
Expand Down
3 changes: 2 additions & 1 deletion src/robot_dart/descriptor/base_descriptor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,14 +11,15 @@ namespace robot_dart {

struct BaseDescriptor {
public:
BaseDescriptor(RobotDARTSimu* simu, size_t desc_dump = 1);
BaseDescriptor(size_t desc_dump = 1);
virtual ~BaseDescriptor() {}

virtual void operator()() = 0;

size_t desc_dump() const;
void set_desc_dump(size_t desc_dump);

void set_simu(RobotDARTSimu* simu) { _simu = simu; }
const RobotDARTSimu* simu() const { return _simu; }

protected:
Expand Down
8 changes: 6 additions & 2 deletions src/robot_dart/gui/base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,11 @@ namespace robot_dart {
public:
Base() {}

Base(RobotDARTSimu*) {}

virtual ~Base() {}

virtual void set_simu(RobotDARTSimu* simu) { _simu = simu; }
const RobotDARTSimu* simu() const { return _simu; }

virtual bool done() const { return false; }

virtual void refresh() {}
Expand All @@ -30,6 +31,9 @@ namespace robot_dart {

virtual size_t width() const { return 0; }
virtual size_t height() const { return 0; }

protected:
RobotDARTSimu* _simu = nullptr;
};
} // namespace gui
} // namespace robot_dart
Expand Down
Loading