blob: 882eb0995a1244af478377735ae33c07d241e522 [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 java.util.HashSet
import java.util.List
import org.eclipse.app4mc.amalthea.model.StringObject
import org.eclipse.app4mc.amalthea.model.Tag
class RosTagGenerator {
// Suppress default constructor
private new() {
throw new IllegalStateException("Utility class");
}
static def String toCpp(Tag tag, String moduleName, HashSet<String> headers, List<String> declarations,
List<String> inits, List<String> calls, List<String> serviceCallbacks) '''
#include <chrono>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
«FOR header : headers»
«header»
«ENDFOR»
using namespace std::chrono_literals;
using std::placeholders::_1;
«FOR serviceCallback : serviceCallbacks»
«serviceCallback»
«ENDFOR»
class «moduleName» : public rclcpp::Node
{
private:
«FOR declaration : declarations»
«declaration»
«ENDFOR»
public:
«moduleName»()
: Node("«moduleName.toLowerCase»")
{
«FOR init : inits»
«init»
«ENDFOR»
}
«FOR call : calls»
«call»
«ENDFOR»
};
int main(int argc, char * argv[])
{
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
«IF tag.customProperties.get('executor_type') !== null»
«IF (tag.customProperties.get('executor_type') as StringObject).value.equals('single_thread')»
rclcpp::executors::SingleThreadedExecutor executor;
«ELSE»
rclcpp::executors::MultiThreadedExecutor executor;
«ENDIF»
«ELSE»
rclcpp::executors::MultiThreadedExecutor executor;
«ENDIF»
auto node = std::make_shared<«moduleName»>();
executor.add_node(node);
executor.spin();
rclcpp::shutdown();
return 0;
}
'''
}