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

Added optimization for copying arrays of simple types from python to C using buffer protocol #129

Merged
merged 3 commits into from
Jun 11, 2021

Conversation

ksuszka
Copy link
Contributor

@ksuszka ksuszka commented Apr 28, 2021

This is rather naive approach to improve perfomance of copying large amount of data from python to C.
I didn't remove old code, but instead I've added a check if data can be accessed using buffer protocol, and if the answer is yes then a sequence is copied in single step, if the answer is no, then fallback to previous method is used.

It seems to work for ROS2 version of carla_ros_bridge where we discovered this issues. It seems to be the same issue as described in ros2/rclpy#763

@sloretz
Copy link
Contributor

sloretz commented Apr 28, 2021

Thanks for the PR! Updating this templated code is no easy task :)

I started a full CI run on Linux to see if that catches anything first Build Status

I didn't remove old code, but instead I've added a check if data can be accessed using buffer protocol, and if the answer is yes then a sequence is copied in single step, if the answer is no, then fallback to previous method is used.

Sounds reasonable to me

PyObject * item = PySequence_Fast_GET_ITEM(seq_field, i);
if (!item) {
Py_DECREF(seq_field);
@[ if isinstance(member.type, AbstractSequence) and isinstance(member.type.value_type, BasicType)]@
Copy link
Contributor Author

@ksuszka ksuszka Apr 28, 2021

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Lines 251-280 is a new code. Lines 281-430 is the old code with an additional level of indentation, used as a backup if PyObject_CheckBuffer call fails.

Copy link

@emersonknapp emersonknapp May 19, 2021

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just as a note for interested parties - github diff view has "Ignore whitespace changes" under the "settings gear" which makes the diff a lot easier to look at in this case

@karl-schulz
Copy link

karl-schulz commented Apr 29, 2021

Hi, I can confirm that this improves the publishing performance and also fixes ros2/rclpy#763 (tested by applying the changes to the foxy branch).

Thank you @ksuszka this is really great!

Copy link
Contributor

@clalancette clalancette left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I've left a couple of comments for consideration.

rosidl_generator_py/resource/_msg_support.c.em Outdated Show resolved Hide resolved
Comment on lines 257 to 259
PyErr_SetString(PyExc_RuntimeError, "unable to get buffer");
Py_DECREF(field);
return false;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Here I'm wondering whether we should fall back to the "slow" method if PyObject_GetBuffer fails. It's not clear to me in which situations it would fail.

Copy link
Contributor Author

@ksuszka ksuszka Apr 30, 2021

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Quote from reference (https://docs.python.org/3/c-api/buffer.html#c.PyObject_GetBuffer): "Send a request to exporter to fill in view as specified by flags. If the exporter cannot provide a buffer of the exact type, it MUST raise PyExc_BufferError, set view->obj to NULL and return -1.".

So, if I understand correctly, in theory it could happen if python structure we try to access is some complex, multidimensional array and we ask for some other shape. But we ask for PyBUF_SIMPLE (https://docs.python.org/3/c-api/buffer.html#shape-strides-suboffsets), so for the simplest possible structure. So it probably will never fail.

However, I'm not a python expert so I'm guessing here.

EDIT: Also, we already check on template level that we are handling AbstractSequence of BasicTypes.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

EDIT: Also, we already check on template level that we are handling AbstractSequence of BasicTypes.

This part doesn't matter, I think. At runtime, if the __convert_from_py function was handed a message that had an attribute for data that we thought should be a buffer, but wasn't, we still might fail here.

But in that case the message would have been not what we were expecting anyway, so any decoding would probably eventually fail. I'm OK with not falling back in this case.

rosidl_generator_py/resource/_msg_support.c.em Outdated Show resolved Hide resolved
Comment on lines 271 to 274
PyErr_SetString(PyExc_RuntimeError, "unable to copy buffer");
PyBuffer_Release(&view);
Py_DECREF(field);
return false;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same question here about whether we should fall back to the slow method.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Quote from reference (https://docs.python.org/3/c-api/buffer.html#c.PyBuffer_ToContiguous): "This function fails if len != src->len.".
As I undrestand it - as we just literally took the value from the src it should never happen. However, just for any future possible change in the bahaviour I would left this check, just in case.

Copy link
Contributor

@clalancette clalancette left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This looks good to me, and should be a great speedup on Python. I'd like to get another review from @sloretz (and CI) before we move forward.

Copy link
Contributor

@sloretz sloretz left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is a great improvement! I just a couple nitpicks in the error handling.

Also, mind rebasing this on top of master? That will help with running CI.

rosidl_generator_py/resource/_msg_support.c.em Outdated Show resolved Hide resolved
rosidl_generator_py/resource/_msg_support.c.em Outdated Show resolved Hide resolved
@sloretz
Copy link
Contributor

sloretz commented Jun 9, 2021

This is a fantastic contribution! It really makes a big difference for arrays of numeric types.

I checked that the non-buffer API case works, but it isn't that important because the setters for array fields set the field to an array.array() instance. A user would have to set the field beginning with an underscore (or monkey patch out the setter) to actually use that case.

Test script
#!/usr/bin/python3
import array
import builtin_interfaces.msg
import collections
import rclpy
from rclpy.node import Node
from rclpy.qos import QoSProfile
from test_msgs.msg import UnboundedSequences
import sys


class NoBuffer(collections.Sequence):

    def __init__(self, seq):
        self._seq = seq

    def __getitem__(self, *args, **kwargs):
        return self._seq.__getitem__(*args, **kwargs)

    def __len__(self):
        return len(self._seq)


class SelfCycler(Node):
    """Publish large messages to itself endlessly."""
    def __init__(self):
        super().__init__("self_cycle_py")

        pub_qos = QoSProfile(depth=10)
        sub_qos = QoSProfile(depth=10)
        self._sub = self.create_subscription(UnboundedSequences, topic="seq_py", callback=self._handle_msg, qos_profile=sub_qos)
        self._pub = self.create_publisher(UnboundedSequences, topic="seq_py", qos_profile=pub_qos)
        self._timer = self.create_timer(0.1, self.publish_msg)

    def publish_msg(self):
        num_items =  327680

        # BROKEN :(
        # self._publish_msg_attr("byte_values", b'\xaa' * num_items)

        self._publish_msg_attr("bool_values", NoBuffer((True,) * num_items))
        self._publish_msg_attr("byte_values", NoBuffer((b'\xaa',) * num_items))
        self._publish_msg_attr("char_values", NoBuffer((234,) * num_items))
        self._publish_msg_attr("float32_values", NoBuffer((3.14,) * num_items))
        self._publish_msg_attr("float64_values", NoBuffer((6.28,) * num_items))
        self._publish_msg_attr("int8_values", NoBuffer((127,) * num_items))
        self._publish_msg_attr("uint8_values", NoBuffer((235,) * num_items))
        self._publish_msg_attr("int16_values", NoBuffer((1234,) * num_items))
        self._publish_msg_attr("uint16_values", NoBuffer((17000,) * num_items))
        self._publish_msg_attr("int32_values", NoBuffer((100123,) * num_items))
        self._publish_msg_attr("uint32_values", NoBuffer((3000123,) * num_items))
        self._publish_msg_attr("int64_values", NoBuffer((42,) * num_items))
        self._publish_msg_attr("uint64_values", NoBuffer((84,) * num_items))
        self._publish_msg_attr("string_values", NoBuffer(("hi",) * num_items))

        self._publish_msg_attr("bool_values", (True,) * num_items)
        self._publish_msg_attr("byte_values", (b'\xaa',) * num_items)
        self._publish_msg_attr("char_values", (234,) * num_items)
        self._publish_msg_attr("float32_values", (3.14,) * num_items)
        self._publish_msg_attr("float64_values", (6.28,) * num_items)
        self._publish_msg_attr("int8_values", (127,) * num_items)
        self._publish_msg_attr("uint8_values", (235,) * num_items)
        self._publish_msg_attr("int16_values", (1234,) * num_items)
        self._publish_msg_attr("uint16_values", (17000,) * num_items)
        self._publish_msg_attr("int32_values", (100123,) * num_items)
        self._publish_msg_attr("uint32_values", (3000123,) * num_items)
        self._publish_msg_attr("int64_values", (42,) * num_items)
        self._publish_msg_attr("uint64_values", (84,) * num_items)
        self._publish_msg_attr("string_values", ("hi",) * num_items)

        self._publish_msg_attr("bool_values", [True,] * num_items)
        self._publish_msg_attr("byte_values", [b'\xaa',] * num_items)
        self._publish_msg_attr("char_values", [234,] * num_items)
        self._publish_msg_attr("float32_values", [3.14,] * num_items)
        self._publish_msg_attr("float64_values", [6.28,] * num_items)
        self._publish_msg_attr("int8_values", [127,] * num_items)
        self._publish_msg_attr("uint8_values", [235,] * num_items)
        self._publish_msg_attr("int16_values", [1234,] * num_items)
        self._publish_msg_attr("uint16_values", [17000,] * num_items)
        self._publish_msg_attr("int32_values", [100123,] * num_items)
        self._publish_msg_attr("uint32_values", [3000123,] * num_items)
        self._publish_msg_attr("int64_values", [42,] * num_items)
        self._publish_msg_attr("uint64_values", [84,] * num_items)
        self._publish_msg_attr("string_values", ["hi",] * num_items)

        self._publish_msg_attr("char_values", array.array('B', [234,] * num_items))
        self._publish_msg_attr("float32_values", array.array('f', [3.14,] * num_items))
        self._publish_msg_attr("float64_values", array.array('d', [6.28,] * num_items))
        self._publish_msg_attr("int8_values", array.array('b', [127,] * num_items))
        self._publish_msg_attr("uint8_values", array.array('B', [235,] * num_items))
        self._publish_msg_attr("int16_values", array.array('h', [1234,] * num_items))
        self._publish_msg_attr("uint16_values", array.array('H', [17000,] * num_items))
        # BROKEN :(
        # self._publish_msg_attr("int32_values", array.array('l', [100123,] * num_items))
        # self._publish_msg_attr("uint32_values", array.array('L', [3000123,] * num_items))
        # self._publish_msg_attr("int64_values", array.array('q', [42,] * num_items))
        # self._publish_msg_attr("uint64_values", array.array('Q', [84,] * num_items))

        sys.exit()

    def _publish_msg_attr(self, msg_attr, value):
        msg = UnboundedSequences()
        setattr(msg, msg_attr, value)

        t1 = self.get_clock().now().to_msg()
        self._pub.publish(msg)
        t2 = self.get_clock().now().to_msg()
        self.get_logger().info(f"{msg_attr} {type(value)} took {self.format_dt(t1, t2)}")

    def format_dt(self, t1: builtin_interfaces.msg.Time, t2: builtin_interfaces.msg.Time):
        """ Helper for formatting the difference between two stamps in microseconds """
        us1 = t1.sec * 1e6 + t1.nanosec // 1e3
        us2 = t2.sec * 1e6 + t2.nanosec // 1e3
        return f"{int(us2 - us1):5} [us]"

    def _handle_msg(self, msg):
        pass  # Nothing to do here


def main(args=None):
    rclpy.init()
    node = SelfCycler()
    try:
        rclpy.spin(node)
    finally:
        node.destroy_node()


if __name__ == '__main__':
    main()
Results on master
[INFO] [1623195713.989881327] [self_cycle_py]: bool_values <class '__main__.NoBuffer'> took 65064 [us]
[INFO] [1623195714.138823820] [self_cycle_py]: byte_values <class '__main__.NoBuffer'> took 65078 [us]
[INFO] [1623195714.381579971] [self_cycle_py]: char_values <class '__main__.NoBuffer'> took  3898 [us]
[INFO] [1623195714.550229209] [self_cycle_py]: float32_values <class '__main__.NoBuffer'> took 10549 [us]
[INFO] [1623195714.720721546] [self_cycle_py]: float64_values <class '__main__.NoBuffer'> took 11546 [us]
[INFO] [1623195714.970193817] [self_cycle_py]: int8_values <class '__main__.NoBuffer'> took  4016 [us]
[INFO] [1623195715.215124704] [self_cycle_py]: uint8_values <class '__main__.NoBuffer'> took  3794 [us]
[INFO] [1623195715.465594131] [self_cycle_py]: int16_values <class '__main__.NoBuffer'> took 10057 [us]
[INFO] [1623195715.715654631] [self_cycle_py]: uint16_values <class '__main__.NoBuffer'> took  9806 [us]
[INFO] [1623195715.971763413] [self_cycle_py]: int32_values <class '__main__.NoBuffer'> took 10592 [us]
[INFO] [1623195716.212935232] [self_cycle_py]: uint32_values <class '__main__.NoBuffer'> took 10460 [us]
[INFO] [1623195716.459274196] [self_cycle_py]: int64_values <class '__main__.NoBuffer'> took  5511 [us]
[INFO] [1623195716.697001717] [self_cycle_py]: uint64_values <class '__main__.NoBuffer'> took  4865 [us]
[INFO] [1623195717.023702700] [self_cycle_py]: string_values <class '__main__.NoBuffer'> took 244059 [us]
[INFO] [1623195717.042494632] [self_cycle_py]: bool_values <class 'tuple'> took  1548 [us]
[INFO] [1623195717.060993832] [self_cycle_py]: byte_values <class 'tuple'> took  1792 [us]
[INFO] [1623195717.108553494] [self_cycle_py]: char_values <class 'tuple'> took  3895 [us]
[INFO] [1623195717.142507722] [self_cycle_py]: float32_values <class 'tuple'> took  9627 [us]
[INFO] [1623195717.176651889] [self_cycle_py]: float64_values <class 'tuple'> took 10167 [us]
[INFO] [1623195717.227831034] [self_cycle_py]: int8_values <class 'tuple'> took  4491 [us]
[INFO] [1623195717.277971306] [self_cycle_py]: uint8_values <class 'tuple'> took  4394 [us]
[INFO] [1623195717.335102504] [self_cycle_py]: int16_values <class 'tuple'> took 11053 [us]
[INFO] [1623195717.389710578] [self_cycle_py]: uint16_values <class 'tuple'> took  9946 [us]
[INFO] [1623195717.442223293] [self_cycle_py]: int32_values <class 'tuple'> took  9908 [us]
[INFO] [1623195717.489922885] [self_cycle_py]: uint32_values <class 'tuple'> took 10574 [us]
[INFO] [1623195717.536908216] [self_cycle_py]: int64_values <class 'tuple'> took  4009 [us]
[INFO] [1623195717.578159363] [self_cycle_py]: uint64_values <class 'tuple'> took  3910 [us]
[INFO] [1623195717.776084602] [self_cycle_py]: string_values <class 'tuple'> took 181596 [us]
[INFO] [1623195717.794193547] [self_cycle_py]: bool_values <class 'list'> took  1369 [us]
[INFO] [1623195717.812611641] [self_cycle_py]: byte_values <class 'list'> took  1626 [us]
[INFO] [1623195717.859447383] [self_cycle_py]: char_values <class 'list'> took  3904 [us]
[INFO] [1623195717.895154971] [self_cycle_py]: float32_values <class 'list'> took 11825 [us]
[INFO] [1623195717.930338661] [self_cycle_py]: float64_values <class 'list'> took 10625 [us]
[INFO] [1623195717.978289517] [self_cycle_py]: int8_values <class 'list'> took  4180 [us]
[INFO] [1623195718.025640987] [self_cycle_py]: uint8_values <class 'list'> took  3949 [us]
[INFO] [1623195718.079544347] [self_cycle_py]: int16_values <class 'list'> took 10764 [us]
[INFO] [1623195718.132896078] [self_cycle_py]: uint16_values <class 'list'> took 10335 [us]
[INFO] [1623195718.186715182] [self_cycle_py]: int32_values <class 'list'> took 10588 [us]
[INFO] [1623195718.235905414] [self_cycle_py]: uint32_values <class 'list'> took 10356 [us]
[INFO] [1623195718.283507342] [self_cycle_py]: int64_values <class 'list'> took  4033 [us]
[INFO] [1623195718.325601239] [self_cycle_py]: uint64_values <class 'list'> took  4091 [us]
[INFO] [1623195718.522702160] [self_cycle_py]: string_values <class 'list'> took 180183 [us]
[INFO] [1623195718.537421971] [self_cycle_py]: char_values <class 'array.array'> took  4822 [us]
[INFO] [1623195718.556528717] [self_cycle_py]: float32_values <class 'array.array'> took 10719 [us]
[INFO] [1623195718.576482634] [self_cycle_py]: float64_values <class 'array.array'> took 10562 [us]
[INFO] [1623195718.591256600] [self_cycle_py]: int8_values <class 'array.array'> took  4608 [us]
[INFO] [1623195718.605320856] [self_cycle_py]: uint8_values <class 'array.array'> took  4311 [us]
[INFO] [1623195718.626135337] [self_cycle_py]: int16_values <class 'array.array'> took 11158 [us]
[INFO] [1623195718.646768185] [self_cycle_py]: uint16_values <class 'array.array'> took 11129 [us]
Results with this PR
[INFO] [1623195780.963380689] [self_cycle_py]: bool_values <class '__main__.NoBuffer'> took 68367 [us]
[INFO] [1623195781.124780865] [self_cycle_py]: byte_values <class '__main__.NoBuffer'> took 76704 [us]
[INFO] [1623195781.389771226] [self_cycle_py]: char_values <class '__main__.NoBuffer'> took   252 [us]
[INFO] [1623195781.556462384] [self_cycle_py]: float32_values <class '__main__.NoBuffer'> took  1552 [us]
[INFO] [1623195781.724900569] [self_cycle_py]: float64_values <class '__main__.NoBuffer'> took  1397 [us]
[INFO] [1623195781.975215139] [self_cycle_py]: int8_values <class '__main__.NoBuffer'> took   250 [us]
[INFO] [1623195782.230622547] [self_cycle_py]: uint8_values <class '__main__.NoBuffer'> took   293 [us]
[INFO] [1623195782.480543196] [self_cycle_py]: int16_values <class '__main__.NoBuffer'> took   291 [us]
[INFO] [1623195782.729770611] [self_cycle_py]: uint16_values <class '__main__.NoBuffer'> took   311 [us]
[INFO] [1623195782.981284070] [self_cycle_py]: int32_values <class '__main__.NoBuffer'> took   897 [us]
[INFO] [1623195783.220575091] [self_cycle_py]: uint32_values <class '__main__.NoBuffer'> took   843 [us]
[INFO] [1623195783.475862916] [self_cycle_py]: int64_values <class '__main__.NoBuffer'> took  2310 [us]
[INFO] [1623195783.719173923] [self_cycle_py]: uint64_values <class '__main__.NoBuffer'> took  1867 [us]
[INFO] [1623195784.086068116] [self_cycle_py]: string_values <class '__main__.NoBuffer'> took 277784 [us]
[INFO] [1623195784.104673597] [self_cycle_py]: bool_values <class 'tuple'> took  1493 [us]
[INFO] [1623195784.123106659] [self_cycle_py]: byte_values <class 'tuple'> took  1744 [us]
[INFO] [1623195784.166476384] [self_cycle_py]: char_values <class 'tuple'> took   246 [us]
[INFO] [1623195784.191412029] [self_cycle_py]: float32_values <class 'tuple'> took   434 [us]
[INFO] [1623195784.217411019] [self_cycle_py]: float64_values <class 'tuple'> took  1403 [us]
[INFO] [1623195784.261776626] [self_cycle_py]: int8_values <class 'tuple'> took   255 [us]
[INFO] [1623195784.305674347] [self_cycle_py]: uint8_values <class 'tuple'> took   257 [us]
[INFO] [1623195784.351714231] [self_cycle_py]: int16_values <class 'tuple'> took   314 [us]
[INFO] [1623195784.398818347] [self_cycle_py]: uint16_values <class 'tuple'> took   320 [us]
[INFO] [1623195784.444154092] [self_cycle_py]: int32_values <class 'tuple'> took   436 [us]
[INFO] [1623195784.481809148] [self_cycle_py]: uint32_values <class 'tuple'> took   494 [us]
[INFO] [1623195784.525865841] [self_cycle_py]: int64_values <class 'tuple'> took   718 [us]
[INFO] [1623195784.563531212] [self_cycle_py]: uint64_values <class 'tuple'> took   682 [us]
[INFO] [1623195784.765877229] [self_cycle_py]: string_values <class 'tuple'> took 185914 [us]
[INFO] [1623195784.783523332] [self_cycle_py]: bool_values <class 'list'> took  1348 [us]
[INFO] [1623195784.800969589] [self_cycle_py]: byte_values <class 'list'> took  1572 [us]
[INFO] [1623195784.846241046] [self_cycle_py]: char_values <class 'list'> took   326 [us]
[INFO] [1623195784.871957117] [self_cycle_py]: float32_values <class 'list'> took   430 [us]
[INFO] [1623195784.898597912] [self_cycle_py]: float64_values <class 'list'> took   723 [us]
[INFO] [1623195784.945617497] [self_cycle_py]: int8_values <class 'list'> took   348 [us]
[INFO] [1623195784.994728133] [self_cycle_py]: uint8_values <class 'list'> took   291 [us]
[INFO] [1623195785.042587106] [self_cycle_py]: int16_values <class 'list'> took   453 [us]
[INFO] [1623195785.091172213] [self_cycle_py]: uint16_values <class 'list'> took   308 [us]
[INFO] [1623195785.137493895] [self_cycle_py]: int32_values <class 'list'> took   490 [us]
[INFO] [1623195785.178155761] [self_cycle_py]: uint32_values <class 'list'> took   491 [us]
[INFO] [1623195785.227621850] [self_cycle_py]: int64_values <class 'list'> took   712 [us]
[INFO] [1623195785.270939707] [self_cycle_py]: uint64_values <class 'list'> took   730 [us]
[INFO] [1623195785.482988367] [self_cycle_py]: string_values <class 'list'> took 193858 [us]
[INFO] [1623195785.492819617] [self_cycle_py]: char_values <class 'array.array'> took   267 [us]
[INFO] [1623195785.501720923] [self_cycle_py]: float32_values <class 'array.array'> took   416 [us]
[INFO] [1623195785.510730501] [self_cycle_py]: float64_values <class 'array.array'> took   630 [us]
[INFO] [1623195785.520222595] [self_cycle_py]: int8_values <class 'array.array'> took   214 [us]
[INFO] [1623195785.529275890] [self_cycle_py]: uint8_values <class 'array.array'> took   184 [us]
[INFO] [1623195785.538551928] [self_cycle_py]: int16_values <class 'array.array'> took   255 [us]
[INFO] [1623195785.548259438] [self_cycle_py]: uint16_values <class 'array.array'> took   283 [us]

ksuszka and others added 2 commits June 9, 2021 20:18
Signed-off-by: ksuszka <ksuszka@autonomous-systems.pl>
Co-authored-by: Chris Lalancette <clalancette@gmail.com>
Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>
@ksuszka ksuszka force-pushed the array-copying-optimization branch from 930c672 to c727729 Compare June 9, 2021 18:19
Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>
@ksuszka ksuszka force-pushed the array-copying-optimization branch from d637f31 to 0510135 Compare June 9, 2021 19:20
@sloretz
Copy link
Contributor

sloretz commented Jun 9, 2021

CI (build: --packages-above-and-dependencies rosidl_generator_py test: --packages-select rosidl_generator_py)

  • Linux Build Status
  • Linux-aarch64 Build Status
  • macOS Build Status
  • Windows Build Status

@sloretz
Copy link
Contributor

sloretz commented Jun 11, 2021

CI LGTM, the warnings on windows are also in the nightly https://ci.ros2.org/view/nightly/job/nightly_win_rel/1961/msbuild/new/

Copy link
Contributor

@sloretz sloretz left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM! Thanks for the PR!

@sloretz
Copy link
Contributor

sloretz commented Oct 6, 2021

@Mergifyio backport galactic

mergify bot pushed a commit that referenced this pull request Oct 6, 2021
…C using buffer protocol (#129)

* Added optimization for copying arrays of simple types from python to C

Signed-off-by: ksuszka <ksuszka@autonomous-systems.pl>

* Apply suggestions from code review

Co-authored-by: Chris Lalancette <clalancette@gmail.com>
Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>

* Remove setting error message twice

Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>

Co-authored-by: Chris Lalancette <clalancette@gmail.com>
(cherry picked from commit 1796dfd)
@mergify
Copy link

mergify bot commented Oct 6, 2021

Command backport galactic: success

Backports have been created

sloretz pushed a commit that referenced this pull request Oct 9, 2021
…C using buffer protocol (#129) (#145)

* Added optimization for copying arrays of simple types from python to C

Signed-off-by: ksuszka <ksuszka@autonomous-systems.pl>

* Apply suggestions from code review

Co-authored-by: Chris Lalancette <clalancette@gmail.com>
Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>

* Remove setting error message twice

Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>

Co-authored-by: Chris Lalancette <clalancette@gmail.com>
(cherry picked from commit 1796dfd)

Co-authored-by: ksuszka <susel@post.pl>
hexonxons pushed a commit to hexonxons/rosidl_python that referenced this pull request Oct 18, 2021
…C using buffer protocol (ros2#129)

* Added optimization for copying arrays of simple types from python to C

Signed-off-by: ksuszka <ksuszka@autonomous-systems.pl>

* Apply suggestions from code review

Co-authored-by: Chris Lalancette <clalancette@gmail.com>
Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>

* Remove setting error message twice

Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>

Co-authored-by: Chris Lalancette <clalancette@gmail.com>
hexonxons pushed a commit to hexonxons/rosidl_python that referenced this pull request Oct 18, 2021
…C using buffer protocol (ros2#129)

* Added optimization for copying arrays of simple types from python to C

Signed-off-by: ksuszka <ksuszka@autonomous-systems.pl>

* Apply suggestions from code review

Co-authored-by: Chris Lalancette <clalancette@gmail.com>
Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>

* Remove setting error message twice

Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>

Co-authored-by: Chris Lalancette <clalancette@gmail.com>
Signed-off-by: Aleksandr Rozhdestvenskii <hexonxons@gmail.com>
@sloretz
Copy link
Contributor

sloretz commented Nov 23, 2021

@Mergifyio backport foxy

mergify bot pushed a commit that referenced this pull request Nov 23, 2021
…C using buffer protocol (#129)

* Added optimization for copying arrays of simple types from python to C

Signed-off-by: ksuszka <ksuszka@autonomous-systems.pl>

* Apply suggestions from code review

Co-authored-by: Chris Lalancette <clalancette@gmail.com>
Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>

* Remove setting error message twice

Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>

Co-authored-by: Chris Lalancette <clalancette@gmail.com>
(cherry picked from commit 1796dfd)
@mergify
Copy link

mergify bot commented Nov 23, 2021

backport foxy

✅ Backports have been created

sloretz pushed a commit that referenced this pull request Dec 10, 2021
…C using buffer protocol (#129) (#146)

* Added optimization for copying arrays of simple types from python to C

Signed-off-by: ksuszka <ksuszka@autonomous-systems.pl>

* Apply suggestions from code review

Co-authored-by: Chris Lalancette <clalancette@gmail.com>
Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>

* Remove setting error message twice

Signed-off-by: Krzysztof Suszka <ksuszka@autonomous-systems.pl>

Co-authored-by: Chris Lalancette <clalancette@gmail.com>
Signed-off-by: Aleksandr Rozhdestvenskii <hexonxons@gmail.com>

Co-authored-by: ksuszka <susel@post.pl>
Co-authored-by: Chris Lalancette <clalancette@gmail.com>
@aditya2592
Copy link

aditya2592 commented Dec 23, 2021

Does this also fix potential issues with CPP to python conversion? I have a CPP service that sends data in the form of sensor_msgs/Image. For image of size 3 x 720 x 1280, it takes 350 ms for the image to be received in a Python client. For an image of size 3 x 480 x 640, it takes 100 ms. Since the time as well as size difference is close to 3, I was wondering if the data copy issue is a factor here as well.

@aprotyas
Copy link
Member

Does this also fix potential issues with CPP to python conversion? I have a CPP service that sends data in the form of sensor_msgs/Image. For image of size 3 x 720 x 1280, it takes 350 ms for the image to be received in a Python client. For an image of size 3 x 480 x 640, it takes 100 ms. Since the time as well as size difference is close to 3, I was wondering if the data copy issue is a factor here as well.

Possibly, are you on Foxy? This patch hasn't been released in Foxy yet, but you could try to compare against Galactic and Rolling if possible.

@aditya2592
Copy link

aditya2592 commented Dec 23, 2021

Does this also fix potential issues with CPP to python conversion? I have a CPP service that sends data in the form of sensor_msgs/Image. For image of size 3 x 720 x 1280, it takes 350 ms for the image to be received in a Python client. For an image of size 3 x 480 x 640, it takes 100 ms. Since the time as well as size difference is close to 3, I was wondering if the data copy issue is a factor here as well.

Possibly, are you on Foxy? This patch hasn't been released in Foxy yet, but you could try to compare against Galactic and Rolling if possible.

I am trying on Galactic (built from source)

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

7 participants