blob: 16d8539521cdf0011c26c2e5f3b404ec9e230569 [file] [log] [blame]
/**
* Copyright (c) 2020-2021 Robert Bosch GmbH.
*
* This program and the accompanying materials are made
* available under the terms of the Eclipse Public License 2.0
* which is available at https://www.eclipse.org/legal/epl-2.0/
*
* SPDX-License-Identifier: EPL-2.0
*
* Contributors:
* Robert Bosch GmbH - initial API and implementation
*/
package org.eclipse.app4mc.slg.ros2.generators
import org.eclipse.app4mc.amalthea.model.ChannelSend
class RosChannelSendUtilsGenerator {
// Suppress default constructor
private new() {
throw new IllegalStateException("Utility class");
}
static def String toCPPHead() '''
#include "channelSendUtils.h"
'''
static def String toCPP(ChannelSend cs) '''
void publish_to_«cs.data.name»(rclcpp::Publisher<std_msgs::msg::String>::SharedPtr& publisher) {
auto message = std_msgs::msg::String();
message.data = "«FOR i : 1..(cs.data.size.numberBytes as int)»A«ENDFOR»";
publisher->publish(message);
}
'''
static def String toHeader() '''
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
'''
static def String toH(ChannelSend cs) '''
void publish_to_«cs.data.name»(rclcpp::Publisher<std_msgs::msg::String>::SharedPtr& publisher);
'''
}