pool_allocated_sensor_msgs.h
Go to the documentation of this file.
1 #pragma once
2 
3 // SPDX-License-Identifier: BSD-3-Clause
4 // SPDX-FileCopyrightText: Czech Technical University in Prague
5 
23 #include <boost/pool/pool_alloc.hpp>
24 
25 #include <sensor_msgs/BatteryState.h>
26 #include <sensor_msgs/CameraInfo.h>
27 #include <sensor_msgs/ChannelFloat32.h>
28 #include <sensor_msgs/CompressedImage.h>
29 #include <sensor_msgs/Image.h>
30 #include <sensor_msgs/JointState.h>
31 #include <sensor_msgs/Joy.h>
32 #include <sensor_msgs/JoyFeedback.h>
33 #include <sensor_msgs/JoyFeedbackArray.h>
34 #include <sensor_msgs/LaserEcho.h>
35 #include <sensor_msgs/LaserScan.h>
36 #include <sensor_msgs/MultiDOFJointState.h>
37 #include <sensor_msgs/MultiEchoLaserScan.h>
38 #include <sensor_msgs/PointCloud.h>
39 #include <sensor_msgs/PointCloud2.h>
40 
41 #include <ros/message_forward.h>
42 
43 namespace sensor_msgs // we cannot change the namespace to cras_msgs :(
44 {
45 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(BatteryState, BatteryStatePoolAllocated, boost::pool_allocator)
46 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(CameraInfo, CameraInfoPoolAllocated, boost::pool_allocator)
47 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(ChannelFloat32, ChannelFloat32PoolAllocated, boost::pool_allocator)
48 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(CompressedImage, CompressedImagePoolAllocated, boost::pool_allocator)
49 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(Image, ImagePoolAllocated, boost::pool_allocator)
50 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(JointState, JointStatePoolAllocated, boost::pool_allocator)
51 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(Joy, JoyPoolAllocated, boost::pool_allocator)
52 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(JoyFeedback, JoyFeedbackPoolAllocated, boost::pool_allocator)
53 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(JoyFeedbackArray, JoyFeedbackArrayPoolAllocated, boost::pool_allocator)
54 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(LaserEcho, LaserEchoPoolAllocated, boost::pool_allocator)
55 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(LaserScan, LaserScanPoolAllocated, boost::pool_allocator)
56 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(MultiDOFJointState, MultiDOFJointStatePoolAllocated, boost::pool_allocator)
57 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(MultiEchoLaserScan, MultiEchoLaserScanPoolAllocated, boost::pool_allocator)
58 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(PointCloud, PointCloudPoolAllocated, boost::pool_allocator)
59 ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(PointCloud2, PointCloud2PoolAllocated, boost::pool_allocator)
60 }
#define ROS_DECLARE_MESSAGE_WITH_ALLOCATOR(msg, new_name, alloc)


cras_msgs
Author(s): Martin Pecka
autogenerated on Thu May 4 2023 02:39:26