-1

Imagine the bin picking scenario:

  • Simulation is setup with ManipulationStation.
  • RGBA & pointcloud can be accessed through lcm channel through pub/sub.
  • Perform a grasp detection using RGBA & pointcloud.

I would like to implement the grasp detection procedure, which will be invoked once from time to time. This meant that the procedure will just stay idle, doing nothing, while waiting for the call. In ROS, I would probably use ROS-Service to achieve this. I would like to ask for a suggestion of best practice to do this in Drake framework.

I have also considered a few designs, but they didn't answer my requirement yet.

  • A stright forward choice would be to use pub/sub through lcm. However, a naive implementation would end up in the grasp detection that would always run/update in the background regardless whether the grasp is necessary.
  • Implemented it as a subclass of LeafSystem, similar to what had been done in RobotLocomotion/6-881-examples. However, if I understand correctly, it would end up in the detection that always run/update in the background also.

P.S. This might not be directly related to the topic. But to achieve the deterministic behaviors for testing in above setup, am I correct that

  • The communication through the network, lcm in this case, should be avoid as suggested in this lecture.
  • And the diagram which connected various systems should be used instead?
  • I need to understand your question better. If everything is running in a single process, even a single Drake diagram, then there are a number of ways to specify the timing semantics of when a System runs (discrete time, continuous time, event-driven). Is that what you need clarity on? Alternatively, there might be a question of how to coordinate timing across multiple processes? Or how to connect Drake with ROS? Which do you mean? – Russ Tedrake Dec 04 '21 at 00:55
  • Sorry for an ambiguous question. It is not about connecting to ROS. I would like to achieve everything within Drake framework. In above question, it is more the question of how to achieve them through multiple processes using lcm (pub/sub), which I kind of imitated the design from [drake/examples/kuka_iiwa_arm/](https://github.com/RobotLocomotion/drake/tree/master/examples/kuka_iiwa_arm). However, if Drake can achieve this by connecting various systems through diagram in a single process and it is a recommended goto in Drake, I would also appreciate a reference on how to specify the timing. – milLII3yway Dec 04 '21 at 05:57

1 Answers1

1

Ok. Thank you for clarifying. The timing semantics are simplest and most crisp in a single process. I prefer to get those right, first, and then introduce LCM/ROS only as a means to split up the computation across multiple processes (for performance, or to use a different compilation unit for a device driver, etc).

You can write your controller to be continuous time or discrete time (as seen in the tutorials). In the vast amount of cases, these will be the right semantics. I believe you are imagining a case where you have an occasional event (e.g. "a new object was detected" or "I need to replan") which would often appear as an RPC service call in ROS. We do have provisions for these in Drake (see e.g. "declare forced events" in LeafSystem), but it's often much cleaner to simply implement these as, e.g. a simple discrete time system that checks its import port and only does work if the input port value has changed in a way to trigger that activity. The overhead of this approach is very small, and the advantage of the easier semantics is that you can use more tools for log analysis, planning, control, verification, etc.

I hope that addresses the question. If you have a specific case that doesn't fit, let us know.

Russ Tedrake
  • 4,703
  • 1
  • 7
  • 10
  • Thank you very much for the answer. It is exactly what I am looking for. My lack of experience in a programming in system diagram, makes it difficult to wrap my head around the concept. – milLII3yway Dec 04 '21 at 17:12