Skip to content

Commit

Permalink
Fix ROSSerialization example.
Browse files Browse the repository at this point in the history
  • Loading branch information
petervdonovan committed Jul 21, 2023
1 parent 75823af commit 80ee05e
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions examples/CCpp/src/ROS/ROSSerialization.lf
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ reactor Clock(offset: time = 0, period: time = 1 sec) {

timer t(0, period)
state count: int = 0
state serialized_msg: rclcpp::SerializedMessage = {= rclcpp::SerializedMessage(0u) =}
state serialized_msg: rclcpp::SerializedMessage* = {= new rclcpp::SerializedMessage(0u) =}

reaction(t) -> y {=
(self->count)++;
Expand All @@ -45,13 +45,13 @@ reactor Clock(offset: time = 0, period: time = 1 sec) {

auto message_header_length = 8u;
auto message_payload_length = 10u;
self->serialized_msg.reserve(message_header_length + message_payload_length);
self->serialized_msg->reserve(message_header_length + message_payload_length);

static rclcpp::Serialization<std_msgs::msg::Int32> serializer_obj;
serializer_obj.serialize_message(msg.get(), &self->serialized_msg);
serializer_obj.serialize_message(msg.get(), self->serialized_msg);

SET_NEW_ARRAY(y, self->serialized_msg.size());
y->value = self->serialized_msg.get_rcl_serialized_message().buffer;
SET_NEW_ARRAY(y, self->serialized_msg->size());
y->value = self->serialized_msg->get_rcl_serialized_message().buffer;
=}
}

Expand Down

0 comments on commit 80ee05e

Please # to comment.