first commit

This commit is contained in:
duongtd 2025-10-30 11:30:16 +07:00
commit 827b8623bc
84 changed files with 5662 additions and 0 deletions

View File

@ -0,0 +1,20 @@
cmake_minimum_required(VERSION 3.10)
project(geometry_msgs)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
if (NOT TARGET std_msgs)
add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/../std_msgs ${CMAKE_BINARY_DIR}/std_msgs_build)
endif()
# Thư vin header-only
add_library(geometry_msgs INTERFACE)
# Include path ti thư mc cha file header
target_include_directories(geometry_msgs INTERFACE
${CMAKE_CURRENT_SOURCE_DIR}/include
)
# Liên kết vi std_msgs nếu bn có file Header.h trong include/std_msgs/
target_link_libraries(geometry_msgs INTERFACE std_msgs)

View File

@ -0,0 +1,26 @@
#ifndef POINT_H
#define POINT_H
#include <cmath>
#include <iostream>
namespace geometry_msgs
{
struct Point
{
double x;
double y;
double z;
// Constructor mặc định
Point() : x(0.0), y(0.0), z(0.0) {}
// Constructor khởi tạo nhanh
Point(double x_, double y_, double z_ = 0.0)
: x(x_), y(y_), z(z_) {}
};
} // namespace geometry_msgs
#endif // POINT_H

View File

@ -0,0 +1,14 @@
#ifndef POINT_32_H
#define POINT_32_H
namespace geometry_msgs
{
struct Point32
{
float x;
float y;
float z;
};
} // namespace geometry_msgs
#endif //POINT_32_H

View File

@ -0,0 +1,21 @@
// # This represents a Point with reference coordinate frame and timestamp
// Header header
// Point point
#ifndef POINT_STAMPED_H
#define POINT_STAMPED_H
#include "std_msgs/Header.h"
#include "geometry_msgs/Point.h"
namespace geometry_msgs
{
struct PointStamped
{
std_msgs::Header header;
geometry_msgs::Point point;
PointStamped() = default;
};
} // namespace geometry_msgs
#endif //POINT_STAMPED_H

View File

@ -0,0 +1,16 @@
#ifndef POLYGON_H
#define POLYGON_H
#include<vector>
#include<geometry_msgs/Point32.h>
namespace geometry_msgs
{
struct Polygon
{
std::vector<geometry_msgs::Point32> points;
};
} // namespace geometry_msgs
#endif //POLYGON_H

View File

@ -0,0 +1,21 @@
// # This represents a Polygon with reference coordinate frame and timestamp
// Header header
// Polygon polygon
#ifndef POLYGON_STAMPED_H
#define POLYGON_STAMPED_H
#include<std_msgs/Header.h>
#include<geometry_msgs/Polygon.h>
namespace geometry_msgs
{
struct PolygonStamped
{
std_msgs::Header header;
Polygon polygon;
};
} // namespace geometry_msgs
#endif //POLYGON_STAMPED_H

View File

@ -0,0 +1,20 @@
#ifndef POSE_H
#define POSE_H
#include <cmath>
#include <iostream>
#include <geometry_msgs/Point.h>
#include <geometry_msgs/Quaternion.h>
namespace geometry_msgs
{
struct Pose
{
Point position;
Quaternion orientation;
};
} // namespace geometry_msgs
#endif // POSE_H

View File

@ -0,0 +1,24 @@
#ifndef QUATERNION_H
#define QUATERNION_H
namespace geometry_msgs
{
struct Quaternion
{
double x;
double y;
double z;
double w;
// Constructor mặc định
Quaternion() : x(0.0), y(0.0), z(0.0), w(0.0) {}
// Constructor khởi tạo nhanh
Quaternion(double x_, double y_, double z_, double w_)
: x(x_), y(y_), z(z_), w(w_) {}
};
} // namespace geometry_msgs
#endif // QUATERNION_H

View File

@ -0,0 +1,18 @@
#ifndef TRANSFORM_H
#define TRANSFORM_H
#include "geometry_msgs/Vector3.h"
#include "geometry_msgs/Quaternion.h"
namespace geometry_msgs
{
struct Transform
{
Vector3 translation;
Quaternion rotation;
};
} // namespace geometry_msgs
#endif // TRANSFORM_H

View File

@ -0,0 +1,20 @@
#ifndef TRANSFORM_STAMPED_H
#define TRANSFORM_STAMPED_H
#include "std_msgs/Header.h"
#include "geometry_msgs/Transform.h"
#include <string>
namespace geometry_msgs
{
struct TransformStamped
{
std_msgs::Header header;
std::string child_frame_id;
Transform transform;
};
} // namespace geometry_msgs
#endif // TRANSFORM_STAMPED_H

View File

@ -0,0 +1,23 @@
#ifndef VECTOR_3_H
#define VECTOR_3_H
namespace geometry_msgs
{
struct Vector3
{
double x;
double y;
double z;
// Constructor mặc định
Vector3() : x(0.0), y(0.0), z(0.0) {}
// Constructor khởi tạo nhanh
Vector3(double x_, double y_, double z_)
: x(x_), y(y_), z(z_) {}
};
} // namespace geometry_msgs
#endif // VECTOR_3_H

View File

@ -0,0 +1,3 @@
# This represents a Vector3 with reference coordinate frame and timestamp
Header header
Vector3 vector

26
nav_msgs/CMakeLists.txt Normal file
View File

@ -0,0 +1,26 @@
cmake_minimum_required(VERSION 3.10)
project(nav_msgs)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
if (NOT TARGET std_msgs)
add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/../std_msgs ${CMAKE_BINARY_DIR}/std_msgs_build)
endif()
if (NOT TARGET geometry_msgs)
add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/../geometry_msgs ${CMAKE_BINARY_DIR}/geometry_msgs_build)
endif()
# Thư vin header-only
add_library(nav_msgs INTERFACE)
# Include path ti thư mc cha file header
target_include_directories(nav_msgs INTERFACE
${CMAKE_CURRENT_SOURCE_DIR}/include
)
# Liên kết vi std_msgs nếu bn có file Header.h trong include/std_msgs/
target_link_libraries(nav_msgs INTERFACE
std_msgs
geometry_msgs
)

View File

@ -0,0 +1,23 @@
#ifndef MAP_META_DATA_H
#define MAP_META_DATA_H
#include <cstdint>
#include <string>
#include <vector>
#include "geometry_msgs/Pose.h"
namespace nav_msgs
{
struct MapMetaData
{
double map_load_time;
float resolution;
uint32_t width;
uint32_t height;
geometry_msgs::Pose origin;
};
}
#endif //MAP_META_DATA_H

View File

@ -0,0 +1,24 @@
#ifndef OCCUPANCY_GRID_H
#define OCCUPANCY_GRID_H
#include <cstdint>
#include <string>
#include <vector>
#include "std_msgs/Header.h"
#include <nav_msgs/MapMetaData.h>
namespace nav_msgs
{
struct OccupancyGrid
{
std_msgs::Header header;
MapMetaData info;
std::vector<uint8_t> data;
};
}
#endif //OCCUPANCY_GRID_H

View File

@ -0,0 +1,25 @@
cmake_minimum_required(VERSION 3.10)
project(sensor_msgs)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
if (NOT TARGET std_msgs)
add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/../std_msgs ${CMAKE_BINARY_DIR}/std_msgs_build)
endif()
# Thư vin header-only
add_library(sensor_msgs INTERFACE)
# Include path ti thư mc cha file header
target_include_directories(sensor_msgs INTERFACE
${CMAKE_CURRENT_SOURCE_DIR}/include
)
# Liên kết vi std_msgs nếu bn có file Header.h trong include/std_msgs/
target_link_libraries(sensor_msgs INTERFACE std_msgs yaml-cpp)
# target_link_libraries(sensor_msgs yaml-cpp)
# To file test ví d
add_executable(test_battery_state test/main.cpp)
target_link_libraries(test_battery_state PRIVATE sensor_msgs)

View File

@ -0,0 +1,7 @@
inflation_layer:
enabled: true
inflate_unknown: false
cost_scaling_factor: 15.0
inflation_radius: 0.55
obstacle_layer:
distance: 0.15

View File

@ -0,0 +1,63 @@
#pragma once
#include "std_msgs/Header.h"
#include <cstdint>
#include <string>
#include <vector>
#include <limits>
namespace sensor_msgs
{
struct BatteryState
{
// ===== Power supply status constants =====
static constexpr uint8_t POWER_SUPPLY_STATUS_UNKNOWN = 0;
static constexpr uint8_t POWER_SUPPLY_STATUS_CHARGING = 1;
static constexpr uint8_t POWER_SUPPLY_STATUS_DISCHARGING = 2;
static constexpr uint8_t POWER_SUPPLY_STATUS_NOT_CHARGING = 3;
static constexpr uint8_t POWER_SUPPLY_STATUS_FULL = 4;
// ===== Power supply health constants =====
static constexpr uint8_t POWER_SUPPLY_HEALTH_UNKNOWN = 0;
static constexpr uint8_t POWER_SUPPLY_HEALTH_GOOD = 1;
static constexpr uint8_t POWER_SUPPLY_HEALTH_OVERHEAT = 2;
static constexpr uint8_t POWER_SUPPLY_HEALTH_DEAD = 3;
static constexpr uint8_t POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4;
static constexpr uint8_t POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5;
static constexpr uint8_t POWER_SUPPLY_HEALTH_COLD = 6;
static constexpr uint8_t POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7;
static constexpr uint8_t POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8;
// ===== Power supply technology (chemistry) constants =====
static constexpr uint8_t POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0;
static constexpr uint8_t POWER_SUPPLY_TECHNOLOGY_NIMH = 1;
static constexpr uint8_t POWER_SUPPLY_TECHNOLOGY_LION = 2;
static constexpr uint8_t POWER_SUPPLY_TECHNOLOGY_LIPO = 3;
static constexpr uint8_t POWER_SUPPLY_TECHNOLOGY_LIFE = 4;
static constexpr uint8_t POWER_SUPPLY_TECHNOLOGY_NICD = 5;
static constexpr uint8_t POWER_SUPPLY_TECHNOLOGY_LIMN = 6;
// ===== Data fields =====
std_msgs::Header header;
float voltage = std::numeric_limits<float>::quiet_NaN(); // [V]
float temperature = std::numeric_limits<float>::quiet_NaN(); // [°C]
float current = std::numeric_limits<float>::quiet_NaN(); // [A]
float charge = std::numeric_limits<float>::quiet_NaN(); // [Ah]
float capacity = std::numeric_limits<float>::quiet_NaN(); // [Ah]
float design_capacity = std::numeric_limits<float>::quiet_NaN(); // [Ah]
float percentage = std::numeric_limits<float>::quiet_NaN(); // 0..1
uint8_t power_supply_status = POWER_SUPPLY_STATUS_UNKNOWN;
uint8_t power_supply_health = POWER_SUPPLY_HEALTH_UNKNOWN;
uint8_t power_supply_technology = POWER_SUPPLY_TECHNOLOGY_UNKNOWN;
bool present = false;
std::vector<float> cell_voltage;
std::vector<float> cell_temperature;
std::string location;
std::string serial_number;
};
} // namespace sensor_msgs

View File

@ -0,0 +1,54 @@
# Time of image acquisition, camera coordinate frame ID
Header header # Header timestamp should be acquisition time of image
uint32 height
uint32 width
string distortion_model
float64[] D
float64[9] K # 3x3 row-major matrix
float64[9] R # 3x3 row-major matrix
float64[12] P # 3x4 row-major matrix
uint32 binning_x
uint32 binning_y
RegionOfInterest roi
#pragma once
#include <string>
#include <vector>
#include "msg/Header.h"
#include "msg/RegionOfInterest.h"
namespace sensor_msgs
{
struct CameraInfo
{
std_msgs::Header header; // thời gian và frame_id
// Calibration parameters
uint32_t height = 0;
uint32_t width = 0;
std::string distortion_model;
std::vector<double> D; // distortion coefficients
double K[9] = {0.0}; // intrinsic matrix
double R[9] = {0.0}; // rectification matrix
double P[12] = {0.0}; // projection matrix
// Operational parameters
uint32_t binning_x = 0;
uint32_t binning_y = 0;
sensor_msgs::RegionOfInterest roi;
};
} // namespace sensor_msgs

View File

@ -0,0 +1,12 @@
#pragma once
#include <string>
#include <vector>
namespace sensor_msgs
{
struct ChannelFloat32
{
std::string name; // Tên của channel (vd: "intensity", "rgb", "u", "v")
std::vector<float> values; // Dữ liệu float32 ứng với từng điểm trong PointCloud
};
} // namespace sensor_msgs

View File

@ -0,0 +1,18 @@
#pragma once
#include <string>
#include <vector>
#include "msg/Header.h"
namespace sensor_msgs
{
struct CompressedImage
{
std_msgs::Header header; // Thông tin thời gian & frame_id
std::string format; // Định dạng nén (jpeg, png, ...)
// Dữ liệu ảnh nén (binary buffer)
std::vector<uint8_t> data;
};
} // namespace sensor_msgs

View File

@ -0,0 +1,17 @@
#pragma once
#include "msg/Header.h"
namespace sensor_msgs
{
struct FluidPressure
{
std_msgs::Header header; // Thông tin thời gian và khung tọa độ
double fluid_pressure; // Áp suất tuyệt đối (đơn vị: Pascal)
double variance; // Phương sai (0 = không xác định)
FluidPressure()
: fluid_pressure(0.0), variance(0.0) {}
};
} // namespace sensor_msgs

View File

@ -0,0 +1,17 @@
#pragma once
#include "msg/Header.h"
namespace sensor_msgs
{
struct Illuminance
{
std_msgs::Header header; // Thông tin thời gian và khung tọa độ
double illuminance; // Độ rọi đo được (đơn vị: Lux)
double variance; // Phương sai (0 = không xác định)
Illuminance()
: illuminance(0.0), variance(0.0) {}
};
} // namespace sensor_msgs

View File

@ -0,0 +1,26 @@
#pragma once
#include <string>
#include <vector>
#include <cstdint>
#include "msg/Header.h"
namespace sensor_msgs
{
struct Image
{
std_msgs::Header header; // Thông tin thời gian và frame
uint32_t height = 0; // Số hàng (pixels theo chiều dọc)
uint32_t width = 0; // Số cột (pixels theo chiều ngang)
std::string encoding; // Kiểu mã hóa (vd: "rgb8", "mono8")
uint8_t is_bigendian = 0; // 0 = little endian
uint32_t step = 0; // Số byte mỗi dòng ảnh
std::vector<uint8_t> data; // Mảng dữ liệu ảnh (kích thước step * height)
Image() = default;
inline size_t size() const { return data.size(); }
inline bool empty() const { return data.empty(); }
};
} // namespace sensor_msgs

View File

@ -0,0 +1,31 @@
#pragma once
#include <array>
#include "msg/Header.h"
#include "geometry_msgs/Quaternion.h"
#include "geometry_msgs/Vector3.h"
namespace sensor_msgs
{
struct Imu
{
std_msgs::Header header; // Thời gian và frame gốc
geometry_msgs::Quaternion orientation; // Góc quay (đơn vị: quaternion)
std::array<double, 9> orientation_covariance; // Ma trận hiệp phương sai (row-major)
geometry_msgs::Vector3 angular_velocity; // Tốc độ góc (rad/s)
std::array<double, 9> angular_velocity_covariance; // Ma trận hiệp phương sai
geometry_msgs::Vector3 linear_acceleration; // Gia tốc tuyến tính (m/s^2)
std::array<double, 9> linear_acceleration_covariance; // Ma trận hiệp phương sai
Imu()
{
orientation_covariance.fill(0.0);
angular_velocity_covariance.fill(0.0);
linear_acceleration_covariance.fill(0.0);
}
};
} // namespace sensor_msgs

View File

@ -0,0 +1,21 @@
#pragma once
#include <string>
#include <vector>
#include "msg/Header.h"
namespace sensor_msgs
{
struct JointState
{
std_msgs::Header header; // Thời điểm và frame ghi nhận trạng thái khớp
std::vector<std::string> name; // Tên từng khớp
std::vector<double> position; // Vị trí (rad hoặc m)
std::vector<double> velocity; // Vận tốc (rad/s hoặc m/s)
std::vector<double> effort; // Mô-men hoặc lực (Nm hoặc N)
JointState() = default;
};
} // namespace sensor_msgs

View File

@ -0,0 +1,17 @@
#pragma once
#include <vector>
#include "msg/Header.h"
namespace sensor_msgs
{
struct Joy
{
std_msgs::Header header; // Thời điểm nhận dữ liệu từ joystick
std::vector<float> axes; // Các giá trị trục analog (ví dụ: X, Y, Z, throttle, ...)
std::vector<int32_t> buttons; // Trạng thái nút bấm (0 = nhả, 1 = nhấn)
Joy() = default;
};
} // namespace sensor_msgs

View File

@ -0,0 +1,24 @@
#ifndef JOY_FEEDBACK_H
#define JOY_FEEDBACK_H
#include <cstdint>
namespace sensor_msgs
{
struct JoyFeedback
{
// Declare of the type of feedback
static constexpr uint8_t TYPE_LED = 0;
static constexpr uint8_t TYPE_RUMBLE = 1;
static constexpr uint8_t TYPE_BUZZER = 2;
uint8_t type; // Loại feedback
uint8_t id; // ID của từng loại feedback
float intensity; // Cường độ (0.0 - 1.0)
};
}
#endif // JOY_FEEDBACK_H

View File

@ -0,0 +1,16 @@
#ifndef JOY_FEEDBACK_ARRAY_H
#define JOY_FEEDBACK_ARRAY_H
#include <vector>
#include "sensor_msgs/JoyFeedback.h"
namespace sensor_msgs
{
struct JoyFeedbackArray
{
std::vector<JoyFeedback> array; // Danh sách các feedback
};
} // namespace sensor_msgs
#endif // JOY_FEEDBACK_ARRAY_H

View File

@ -0,0 +1,16 @@
#ifndef LASER_ECHO_H
#define LASER_ECHO_H
#include <vector>
namespace sensor_msgs
{
struct LaserEcho
{
// Mảng chứa nhiều giá trị đo (range hoặc intensity)
// Tất cả đều thuộc cùng một góc quét
std::vector<float> echoes;
};
}
#endif // LASER_ECHO_H

View File

@ -0,0 +1,34 @@
#ifndef LASER_SCAN_H
#define LASER_SCAN_H
#include <vector>
#include "std_msgs/Header.h"
namespace sensor_msgs
{
struct LaserScan
{
std_msgs::Header header; // Thời gian và frame của phép đo
// Góc bắt đầu và kết thúc của tia quét [rad]
float angle_min = 0.0f;
float angle_max = 0.0f;
float angle_increment = 0.0f; // Khoảng cách góc giữa hai tia quét liên tiếp [rad]
// Thông tin về thời gian quét
float time_increment = 0.0f; // Thời gian giữa hai phép đo liên tiếp [s]
float scan_time = 0.0f; // Thời gian hoàn tất một lần quét [s]
// Giới hạn khoảng đo
float range_min = 0.0f; // Giá trị khoảng cách nhỏ nhất [m]
float range_max = 0.0f; // Giá trị khoảng cách lớn nhất [m]
// Dữ liệu chính của laser
std::vector<float> ranges; // Dữ liệu khoảng cách [m]
std::vector<float> intensities; // Cường độ phản xạ (đơn vị phụ thuộc thiết bị)
LaserScan() = default;
};
}
#endif // LASER_SCAN_H

View File

@ -0,0 +1,32 @@
#ifndef MULTI_ECHO_LASER_SCAN_H
#define MULTI_ECHO_LASER_SCAN_H
#include <vector>
#include "msg/Header.h"
#include "msg/LaserEcho.h" // Định nghĩa struct LaserEcho (float32[] echoes)
namespace sensor_msgs
{
struct MultiEchoLaserScan
{
std_msgs::Header header; // Thông tin thời gian & frame của phép đo
float angle_min = 0.0f; // Góc bắt đầu quét (radians)
float angle_max = 0.0f; // Góc kết thúc quét (radians)
float angle_increment = 0.0f; // Độ tăng góc giữa 2 tia liên tiếp (radians)
float time_increment = 0.0f; // Thời gian giữa 2 phép đo (seconds)
float scan_time = 0.0f; // Thời gian quét toàn bộ (seconds)
float range_min = 0.0f; // Khoảng cách đo nhỏ nhất (m)
float range_max = 0.0f; // Khoảng cách đo lớn nhất (m)
std::vector<LaserEcho> ranges; // Dữ liệu khoảng cách (m)
std::vector<LaserEcho> intensities; // Dữ liệu cường độ (tùy chọn)
MultiEchoLaserScan() = default;
};
}
#endif // MULTI_ECHO_LASER_SCAN_H

View File

@ -0,0 +1,24 @@
#ifndef POINTCLOUD_H
#define POINTCLOUD_H
#include <vector>
#include <string>
#include "std_msgs/Header.h"
#include "geometry_msgs/Point32.h"
#include "sensor_msgs/ChannelFloat32.h"
namespace sensor_msgs
{
struct PointCloud
{
std_msgs::Header header; // Thông tin thời gian & frame của dữ liệu
std::vector<geometry_msgs::Point32> points; // Danh sách các điểm 3D (x, y, z)
std::vector<ChannelFloat32> channels; // Dữ liệu phụ đi kèm (vd: "intensity", "rgb")
PointCloud() = default;
};
}
#endif // POINTCLOUD_H

View File

@ -0,0 +1,34 @@
#ifndef POINTCLOUD2_H
#define POINTCLOUD2_H
#include <cstdint>
#include <string>
#include <vector>
#include "std_msgs/Header.h"
#include "sensor_msgs/PointField.h"
namespace sensor_msgs
{
struct PointCloud2
{
std_msgs::Header header; // Thời gian và frame của dữ liệu
uint32_t height = 1; // Số hàng (1 nếu là point cloud 1D)
uint32_t width = 0; // Số lượng điểm trên mỗi hàng (tổng điểm = height * width)
std::vector<PointField> fields; // Thông tin layout của từng trường trong dữ liệu (vd: x, y, z, intensity,...)
bool is_bigendian = false; // true nếu dữ liệu lưu ở dạng big-endian
uint32_t point_step = 0; // Số byte cho mỗi điểm
uint32_t row_step = 0; // Số byte cho mỗi hàng
std::vector<uint8_t> data; // Dữ liệu nhị phân (raw bytes), kích thước = row_step * height
bool is_dense = false; // true nếu không có điểm NaN hoặc vô hiệu
PointCloud2() = default;
};
}
#endif // POINTCLOUD2_H

View File

@ -0,0 +1,31 @@
#ifndef POINTFIELD_H
#define POINTFIELD_H
#include <cstdint>
#include <string>
namespace sensor_msgs
{
struct PointField
{
// Các hằng số kiểu dữ liệu (theo chuẩn ROS)
static constexpr uint8_t INT8 = 1;
static constexpr uint8_t UINT8 = 2;
static constexpr uint8_t INT16 = 3;
static constexpr uint8_t UINT16 = 4;
static constexpr uint8_t INT32 = 5;
static constexpr uint8_t UINT32 = 6;
static constexpr uint8_t FLOAT32 = 7;
static constexpr uint8_t FLOAT64 = 8;
std::string name; // Tên trường (vd: "x", "y", "z", "intensity")
uint32_t offset = 0; // Vị trí byte bắt đầu trong cấu trúc mỗi điểm
uint8_t datatype = 0; // Kiểu dữ liệu (sử dụng các hằng ở trên)
uint32_t count = 0; // Số phần tử trong trường (vd: 3 cho vector3)
PointField() = default;
};
}
#endif // POINTFIELD_H

View File

@ -0,0 +1,28 @@
#ifndef RANGE_H
#define RANGE_H
#include <cstdint>
#include "Header.h" // Header tương tự std_msgs/Header
namespace sensor_msgs
{
struct Range
{
// Các hằng số loại bức xạ (radiation type)
static constexpr uint8_t ULTRASOUND = 0;
static constexpr uint8_t INFRARED = 1;
Header header; // Thời gian đo và frame_id
uint8_t radiation_type = ULTRASOUND; // Loại cảm biến (âm thanh, IR, v.v.)
float field_of_view = 0.0f; // Góc mở của cảm biến [rad]
float min_range = 0.0f; // Khoảng cách nhỏ nhất [m]
float max_range = 0.0f; // Khoảng cách lớn nhất [m]
float range = 0.0f; // Khoảng cách đo được [m]
Range() = default;
};
}
#endif // RANGE_H

View File

@ -0,0 +1,21 @@
#ifndef REGION_OF_INTEREST_H
#define REGION_OF_INTEREST_H
#include <cstdint>
namespace sensor_msgs
{
struct RegionOfInterest
{
uint32_t x_offset = 0; // Pixel ngoài cùng bên trái của ROI
uint32_t y_offset = 0; // Pixel ngoài cùng bên trên của ROI
uint32_t height = 0; // Chiều cao vùng ROI
uint32_t width = 0; // Chiều rộng vùng ROI
bool do_rectify = false; // Có cần tính toán lại ROI sau khi hiệu chỉnh ảnh không
RegionOfInterest() = default;
};
}
#endif // REGION_OF_INTEREST_H

View File

@ -0,0 +1,19 @@
#ifndef RELATIVE_HUMIDITY_H
#define RELATIVE_HUMIDITY_H
#include <cstdint>
#include "msg/Header.h" // Giả định bạn đã có struct Header tương tự ROS std_msgs/Header
namespace sensor_msgs
{
struct RelativeHumidity
{
Header header; // Thời điểm đo và khung tọa độ cảm biến
double relative_humidity = 0.0; // Độ ẩm tương đối (0.0 - 1.0)
double variance = 0.0; // Phương sai, 0 nghĩa là "không biết"
RelativeHumidity() = default;
};
}
#endif // RELATIVE_HUMIDITY_H

View File

@ -0,0 +1,19 @@
#ifndef TEMPERATURE_H
#define TEMPERATURE_H
#include <cstdint>
#include "msg/Header.h" // Định nghĩa struct Header tương tự std_msgs/Header
namespace sensor_msgs
{
struct Temperature
{
Header header; // Thông tin thời gian và vị trí cảm biến
double temperature = 0.0; // Nhiệt độ đo được (°C)
double variance = 0.0; // Phương sai, 0 nghĩa là "không biết"
Temperature() = default;
};
}
#endif // TEMPERATURE_H

View File

@ -0,0 +1,20 @@
#ifndef TIMEREFERENCE_H
#define TIMEREFERENCE_H
#include <string>
#include "msg/Header.h" // Định nghĩa struct Header tương tự std_msgs/Header
namespace sensor_msgs
{
struct TimeReference
{
Header header; // stamp: thời điểm đo (theo đồng hồ hệ thống)
// frame_id: không sử dụng trong message này
double time_ref = 0.0; // Thời gian từ nguồn thời gian bên ngoài (giây)
std::string source; // Tên của nguồn thời gian (tùy chọn)
TimeReference() = default;
};
}
#endif // TIMEREFERENCE_H

View File

@ -0,0 +1,51 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2010, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
#ifndef SENSOR_MSGS_DISTORTION_MODELS_H
#define SENSOR_MSGS_DISTORTION_MODELS_H
#include <string>
namespace sensor_msgs
{
namespace distortion_models
{
const std::string PLUMB_BOB = "plumb_bob";
const std::string RATIONAL_POLYNOMIAL = "rational_polynomial";
const std::string EQUIDISTANT = "equidistant";
}
}
#endif

View File

@ -0,0 +1,70 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
#ifndef FILLIMAGE_HH
#define FILLIMAGE_HH
#include "sensor_msgs/Image.h"
#include "sensor_msgs/image_encodings.h"
namespace sensor_msgs
{
static inline bool fillImage(Image& image,
const std::string& encoding_arg,
uint32_t rows_arg,
uint32_t cols_arg,
uint32_t step_arg,
const void* data_arg)
{
image.encoding = encoding_arg;
image.height = rows_arg;
image.width = cols_arg;
image.step = step_arg;
size_t st0 = (step_arg * rows_arg);
image.data.resize(st0);
memcpy(&image.data[0], data_arg, st0);
image.is_bigendian = 0;
return true;
}
static inline void clearImage(Image& image)
{
image.data.resize(0);
}
}
#endif

View File

@ -0,0 +1,233 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2009, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
#ifndef SENSOR_MSGS_IMAGE_ENCODINGS_H
#define SENSOR_MSGS_IMAGE_ENCODINGS_H
#include <cstdlib>
#include <stdexcept>
#include <string>
namespace sensor_msgs
{
namespace image_encodings
{
const std::string RGB8 = "rgb8";
const std::string RGBA8 = "rgba8";
const std::string RGB16 = "rgb16";
const std::string RGBA16 = "rgba16";
const std::string BGR8 = "bgr8";
const std::string BGRA8 = "bgra8";
const std::string BGR16 = "bgr16";
const std::string BGRA16 = "bgra16";
const std::string MONO8="mono8";
const std::string MONO16="mono16";
// OpenCV CvMat types
const std::string TYPE_8UC1="8UC1";
const std::string TYPE_8UC2="8UC2";
const std::string TYPE_8UC3="8UC3";
const std::string TYPE_8UC4="8UC4";
const std::string TYPE_8SC1="8SC1";
const std::string TYPE_8SC2="8SC2";
const std::string TYPE_8SC3="8SC3";
const std::string TYPE_8SC4="8SC4";
const std::string TYPE_16UC1="16UC1";
const std::string TYPE_16UC2="16UC2";
const std::string TYPE_16UC3="16UC3";
const std::string TYPE_16UC4="16UC4";
const std::string TYPE_16SC1="16SC1";
const std::string TYPE_16SC2="16SC2";
const std::string TYPE_16SC3="16SC3";
const std::string TYPE_16SC4="16SC4";
const std::string TYPE_32SC1="32SC1";
const std::string TYPE_32SC2="32SC2";
const std::string TYPE_32SC3="32SC3";
const std::string TYPE_32SC4="32SC4";
const std::string TYPE_32FC1="32FC1";
const std::string TYPE_32FC2="32FC2";
const std::string TYPE_32FC3="32FC3";
const std::string TYPE_32FC4="32FC4";
const std::string TYPE_64FC1="64FC1";
const std::string TYPE_64FC2="64FC2";
const std::string TYPE_64FC3="64FC3";
const std::string TYPE_64FC4="64FC4";
// Bayer encodings
const std::string BAYER_RGGB8="bayer_rggb8";
const std::string BAYER_BGGR8="bayer_bggr8";
const std::string BAYER_GBRG8="bayer_gbrg8";
const std::string BAYER_GRBG8="bayer_grbg8";
const std::string BAYER_RGGB16="bayer_rggb16";
const std::string BAYER_BGGR16="bayer_bggr16";
const std::string BAYER_GBRG16="bayer_gbrg16";
const std::string BAYER_GRBG16="bayer_grbg16";
// Miscellaneous
// This is the UYVY version of YUV422 codec http://www.fourcc.org/yuv.php#UYVY
// with an 8-bit depth
const std::string YUV422="yuv422";
// Prefixes for abstract image encodings
const std::string ABSTRACT_ENCODING_PREFIXES[] = {
"8UC", "8SC", "16UC", "16SC", "32SC", "32FC", "64FC"};
// Utility functions for inspecting an encoding string
static inline bool isColor(const std::string& encoding)
{
return encoding == RGB8 || encoding == BGR8 ||
encoding == RGBA8 || encoding == BGRA8 ||
encoding == RGB16 || encoding == BGR16 ||
encoding == RGBA16 || encoding == BGRA16;
}
static inline bool isMono(const std::string& encoding)
{
return encoding == MONO8 || encoding == MONO16;
}
static inline bool isBayer(const std::string& encoding)
{
return encoding == BAYER_RGGB8 || encoding == BAYER_BGGR8 ||
encoding == BAYER_GBRG8 || encoding == BAYER_GRBG8 ||
encoding == BAYER_RGGB16 || encoding == BAYER_BGGR16 ||
encoding == BAYER_GBRG16 || encoding == BAYER_GRBG16;
}
static inline bool hasAlpha(const std::string& encoding)
{
return encoding == RGBA8 || encoding == BGRA8 ||
encoding == RGBA16 || encoding == BGRA16;
}
static inline int numChannels(const std::string& encoding)
{
// First do the common-case encodings
if (encoding == MONO8 ||
encoding == MONO16)
return 1;
if (encoding == BGR8 ||
encoding == RGB8 ||
encoding == BGR16 ||
encoding == RGB16)
return 3;
if (encoding == BGRA8 ||
encoding == RGBA8 ||
encoding == BGRA16 ||
encoding == RGBA16)
return 4;
if (encoding == BAYER_RGGB8 ||
encoding == BAYER_BGGR8 ||
encoding == BAYER_GBRG8 ||
encoding == BAYER_GRBG8 ||
encoding == BAYER_RGGB16 ||
encoding == BAYER_BGGR16 ||
encoding == BAYER_GBRG16 ||
encoding == BAYER_GRBG16)
return 1;
// Now all the generic content encodings
// TODO: Rewrite with regex when ROS supports C++11
for (size_t i=0; i < sizeof(ABSTRACT_ENCODING_PREFIXES) / sizeof(*ABSTRACT_ENCODING_PREFIXES); i++)
{
std::string prefix = ABSTRACT_ENCODING_PREFIXES[i];
if (encoding.substr(0, prefix.size()) != prefix)
continue;
if (encoding.size() == prefix.size())
return 1; // ex. 8UC -> 1
int n_channel = atoi(encoding.substr(prefix.size(),
encoding.size() - prefix.size()).c_str()); // ex. 8UC5 -> 5
if (n_channel != 0)
return n_channel; // valid encoding string
}
if (encoding == YUV422)
return 2;
throw std::runtime_error("Unknown encoding " + encoding);
return -1;
}
static inline int bitDepth(const std::string& encoding)
{
if (encoding == MONO16)
return 16;
if (encoding == MONO8 ||
encoding == BGR8 ||
encoding == RGB8 ||
encoding == BGRA8 ||
encoding == RGBA8 ||
encoding == BAYER_RGGB8 ||
encoding == BAYER_BGGR8 ||
encoding == BAYER_GBRG8 ||
encoding == BAYER_GRBG8)
return 8;
if (encoding == MONO16 ||
encoding == BGR16 ||
encoding == RGB16 ||
encoding == BGRA16 ||
encoding == RGBA16 ||
encoding == BAYER_RGGB16 ||
encoding == BAYER_BGGR16 ||
encoding == BAYER_GBRG16 ||
encoding == BAYER_GRBG16)
return 16;
// Now all the generic content encodings
// TODO: Rewrite with regex when ROS supports C++11
for (size_t i=0; i < sizeof(ABSTRACT_ENCODING_PREFIXES) / sizeof(*ABSTRACT_ENCODING_PREFIXES); i++)
{
std::string prefix = ABSTRACT_ENCODING_PREFIXES[i];
if (encoding.substr(0, prefix.size()) != prefix)
continue;
if (encoding.size() == prefix.size())
return atoi(prefix.c_str()); // ex. 8UC -> 8
int n_channel = atoi(encoding.substr(prefix.size(),
encoding.size() - prefix.size()).c_str()); // ex. 8UC10 -> 10
if (n_channel != 0)
return atoi(prefix.c_str()); // valid encoding string
}
if (encoding == YUV422)
return 8;
throw std::runtime_error("Unknown encoding " + encoding);
return -1;
}
}
}
#endif

View File

@ -0,0 +1,417 @@
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2013, Open Source Robotics Foundation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Open Source Robotics Foundation nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef SENSOR_MSGS_IMPL_POINT_CLOUD_ITERATOR_H
#define SENSOR_MSGS_IMPL_POINT_CLOUD_ITERATOR_H
#include <sensor_msgs/PointCloud2.h>
#include <cstdarg>
#include <sstream>
#include <string>
#include <vector>
/**
* \brief Private implementation used by PointCloud2Iterator
* \author Vincent Rabaud
*/
namespace
{
/** Return the size of a datatype (which is an enum of sensor_msgs::PointField::) in bytes
* @param datatype one of the enums of sensor_msgs::PointField::
*/
inline int sizeOfPointField(int datatype)
{
if ((datatype == sensor_msgs::PointField::INT8) || (datatype == sensor_msgs::PointField::UINT8))
return 1;
else if ((datatype == sensor_msgs::PointField::INT16) || (datatype == sensor_msgs::PointField::UINT16))
return 2;
else if ((datatype == sensor_msgs::PointField::INT32) || (datatype == sensor_msgs::PointField::UINT32) ||
(datatype == sensor_msgs::PointField::FLOAT32))
return 4;
else if (datatype == sensor_msgs::PointField::FLOAT64)
return 8;
else
{
std::stringstream err;
err << "PointField of type " << datatype << " does not exist";
throw std::runtime_error(err.str());
}
return -1;
}
/** Private function that adds a PointField to the "fields" member of a PointCloud2
* @param cloud_msg the PointCloud2 to add a field to
* @param name the name of the field
* @param count the number of elements in the PointField
* @param datatype the datatype of the elements
* @param offset the offset of that element
* @return the offset of the next PointField that will be added to the PointCLoud2
*/
inline int addPointField(sensor_msgs::PointCloud2 &cloud_msg, const std::string &name, int count, int datatype,
int offset)
{
sensor_msgs::PointField point_field;
point_field.name = name;
point_field.count = count;
point_field.datatype = datatype;
point_field.offset = offset;
cloud_msg.fields.push_back(point_field);
// Update the offset
return offset + point_field.count * sizeOfPointField(datatype);
}
}
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
namespace sensor_msgs
{
inline PointCloud2Modifier::PointCloud2Modifier(PointCloud2& cloud_msg) : cloud_msg_(cloud_msg)
{
}
inline size_t PointCloud2Modifier::size() const
{
return cloud_msg_.data.size() / cloud_msg_.point_step;
}
inline void PointCloud2Modifier::reserve(size_t size)
{
cloud_msg_.data.reserve(size * cloud_msg_.point_step);
}
inline void PointCloud2Modifier::resize(size_t size)
{
cloud_msg_.data.resize(size * cloud_msg_.point_step);
// Update height/width
if (cloud_msg_.height == 1) {
cloud_msg_.width = size;
cloud_msg_.row_step = size * cloud_msg_.point_step;
} else
if (cloud_msg_.width == 1)
cloud_msg_.height = size;
else {
cloud_msg_.height = 1;
cloud_msg_.width = size;
cloud_msg_.row_step = size * cloud_msg_.point_step;
}
}
inline void PointCloud2Modifier::clear()
{
cloud_msg_.data.clear();
// Update height/width
if (cloud_msg_.height == 1)
cloud_msg_.row_step = cloud_msg_.width = 0;
else
if (cloud_msg_.width == 1)
cloud_msg_.height = 0;
else
cloud_msg_.row_step = cloud_msg_.width = cloud_msg_.height = 0;
}
/**
* @brief Function setting some fields in a PointCloud and adjusting the
* internals of the PointCloud2
* @param n_fields the number of fields to add. The fields are given as
* triplets: name of the field as char*, number of elements in the
* field, the datatype of the elements in the field
*
* E.g, you create your PointCloud2 message with XYZ/RGB as follows:
* <PRE>
* setPointCloud2FieldsByString(cloud_msg, 4, "x", 1, sensor_msgs::PointField::FLOAT32,
* "y", 1, sensor_msgs::PointField::FLOAT32,
* "z", 1, sensor_msgs::PointField::FLOAT32,
* "rgb", 1, sensor_msgs::PointField::FLOAT32);
* </PRE>
* WARNING: THIS DOES NOT TAKE INTO ACCOUNT ANY PADDING AS DONE UNTIL HYDRO
* For simple usual cases, the overloaded setPointCloud2FieldsByString is what you want.
*/
inline void PointCloud2Modifier::setPointCloud2Fields(int n_fields, ...)
{
cloud_msg_.fields.clear();
cloud_msg_.fields.reserve(n_fields);
va_list vl;
va_start(vl, n_fields);
int offset = 0;
for (int i = 0; i < n_fields; ++i) {
// Create the corresponding PointField
std::string name(va_arg(vl, char*));
int count(va_arg(vl, int));
int datatype(va_arg(vl, int));
offset = addPointField(cloud_msg_, name, count, datatype, offset);
}
va_end(vl);
// Resize the point cloud accordingly
cloud_msg_.point_step = offset;
cloud_msg_.row_step = cloud_msg_.width * cloud_msg_.point_step;
cloud_msg_.data.resize(cloud_msg_.height * cloud_msg_.row_step);
}
/**
* @brief Function setting some fields in a PointCloud and adjusting the
* internals of the PointCloud2
* @param n_fields the number of fields to add. The fields are given as
* strings: "xyz" (3 floats), "rgb" (3 uchar stacked in a float),
* "rgba" (4 uchar stacked in a float)
* @return void
*
* WARNING: THIS FUNCTION DOES ADD ANY NECESSARY PADDING TRANSPARENTLY
*/
inline void PointCloud2Modifier::setPointCloud2FieldsByString(int n_fields, ...)
{
cloud_msg_.fields.clear();
cloud_msg_.fields.reserve(n_fields);
va_list vl;
va_start(vl, n_fields);
int offset = 0;
for (int i = 0; i < n_fields; ++i) {
// Create the corresponding PointFields
std::string
field_name = std::string(va_arg(vl, char*));
if (field_name == "xyz") {
sensor_msgs::PointField point_field;
// Do x, y and z
offset = addPointField(cloud_msg_, "x", 1, sensor_msgs::PointField::FLOAT32, offset);
offset = addPointField(cloud_msg_, "y", 1, sensor_msgs::PointField::FLOAT32, offset);
offset = addPointField(cloud_msg_, "z", 1, sensor_msgs::PointField::FLOAT32, offset);
offset += sizeOfPointField(sensor_msgs::PointField::FLOAT32);
} else
if ((field_name == "rgb") || (field_name == "rgba")) {
offset = addPointField(cloud_msg_, field_name, 1, sensor_msgs::PointField::FLOAT32, offset);
offset += 3 * sizeOfPointField(sensor_msgs::PointField::FLOAT32);
} else
throw std::runtime_error("Field " + field_name + " does not exist");
}
va_end(vl);
// Resize the point cloud accordingly
cloud_msg_.point_step = offset;
cloud_msg_.row_step = cloud_msg_.width * cloud_msg_.point_step;
cloud_msg_.data.resize(cloud_msg_.height * cloud_msg_.row_step);
}
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
namespace impl
{
/**
*/
template<typename T, typename TT, typename U, typename C, template <typename> class V>
PointCloud2IteratorBase<T, TT, U, C, V>::PointCloud2IteratorBase() : data_char_(0), data_(0), data_end_(0)
{
}
/**
* @param cloud_msg_ The PointCloud2 to iterate upon
* @param field_name The field to iterate upon
*/
template<typename T, typename TT, typename U, typename C, template <typename> class V>
PointCloud2IteratorBase<T, TT, U, C, V>::PointCloud2IteratorBase(C &cloud_msg, const std::string &field_name)
{
int offset = set_field(cloud_msg, field_name);
data_char_ = cloud_msg.data.data() + offset;
data_ = reinterpret_cast<TT*>(data_char_);
data_end_ = reinterpret_cast<TT*>(data_char_ + cloud_msg.data.size());
}
/** Assignment operator
* @param iter the iterator to copy data from
* @return a reference to *this
*/
template<typename T, typename TT, typename U, typename C, template <typename> class V>
V<T>& PointCloud2IteratorBase<T, TT, U, C, V>::operator =(const V<T> &iter)
{
if (this != &iter)
{
point_step_ = iter.point_step_;
data_char_ = iter.data_char_;
data_ = iter.data_;
data_end_ = iter.data_end_;
is_bigendian_ = iter.is_bigendian_;
}
return *this;
}
/** Access the i th element starting at the current pointer (useful when a field has several elements of the same
* type)
* @param i
* @return a reference to the i^th value from the current position
*/
template<typename T, typename TT, typename U, typename C, template <typename> class V>
TT& PointCloud2IteratorBase<T, TT, U, C, V>::operator [](size_t i) const
{
return *(data_ + i);
}
/** Dereference the iterator. Equivalent to accessing it through [0]
* @return the value to which the iterator is pointing
*/
template<typename T, typename TT, typename U, typename C, template <typename> class V>
TT& PointCloud2IteratorBase<T, TT, U, C, V>::operator *() const
{
return *data_;
}
/** Increase the iterator to the next element
* @return a reference to the updated iterator
*/
template<typename T, typename TT, typename U, typename C, template <typename> class V>
V<T>& PointCloud2IteratorBase<T, TT, U, C, V>::operator ++()
{
data_char_ += point_step_;
data_ = reinterpret_cast<TT*>(data_char_);
return *static_cast<V<T>*>(this);
}
/** Basic pointer addition
* @param i the amount to increase the iterator by
* @return an iterator with an increased position
*/
template<typename T, typename TT, typename U, typename C, template <typename> class V>
V<T> PointCloud2IteratorBase<T, TT, U, C, V>::operator +(int i)
{
V<T> res = *static_cast<V<T>*>(this);
res.data_char_ += i*point_step_;
res.data_ = reinterpret_cast<TT*>(res.data_char_);
return res;
}
/** Increase the iterator by a certain amount
* @return a reference to the updated iterator
*/
template<typename T, typename TT, typename U, typename C, template <typename> class V>
V<T>& PointCloud2IteratorBase<T, TT, U, C, V>::operator +=(int i)
{
data_char_ += i*point_step_;
data_ = reinterpret_cast<TT*>(data_char_);
return *static_cast<V<T>*>(this);
}
/** Compare to another iterator
* @return whether the current iterator points to a different address than the other one
*/
template<typename T, typename TT, typename U, typename C, template <typename> class V>
bool PointCloud2IteratorBase<T, TT, U, C, V>::operator !=(const V<T>& iter) const
{
return iter.data_ != data_;
}
/** Return the end iterator
* @return the end iterator (useful when performing normal iterator processing with ++)
*/
template<typename T, typename TT, typename U, typename C, template <typename> class V>
V<T> PointCloud2IteratorBase<T, TT, U, C, V>::end() const
{
V<T> res = *static_cast<const V<T>*>(this);
res.data_ = data_end_;
return res;
}
/** Common code to set the field of the PointCloud2
* @param cloud_msg the PointCloud2 to modify
* @param field_name the name of the field to iterate upon
* @return the offset at which the field is found
*/
template<typename T, typename TT, typename U, typename C, template <typename> class V>
int PointCloud2IteratorBase<T, TT, U, C, V>::set_field(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name)
{
is_bigendian_ = cloud_msg.is_bigendian;
point_step_ = cloud_msg.point_step;
// make sure the channel is valid
std::vector<sensor_msgs::PointField>::const_iterator field_iter = cloud_msg.fields.begin(), field_end =
cloud_msg.fields.end();
while ((field_iter != field_end) && (field_iter->name != field_name))
++field_iter;
if (field_iter == field_end) {
// Handle the special case of r,g,b,a (we assume they are understood as the channels of an rgb or rgba field)
if ((field_name == "r") || (field_name == "g") || (field_name == "b") || (field_name == "a"))
{
// Check that rgb or rgba is present
field_iter = cloud_msg.fields.begin();
while ((field_iter != field_end) && (field_iter->name != "rgb") && (field_iter->name != "rgba"))
++field_iter;
if (field_iter == field_end)
throw std::runtime_error("Field " + field_name + " does not exist");
if (field_name == "r")
{
if (is_bigendian_)
return field_iter->offset + 1;
else
return field_iter->offset + 2;
}
if (field_name == "g")
{
if (is_bigendian_)
return field_iter->offset + 2;
else
return field_iter->offset + 1;
}
if (field_name == "b")
{
if (is_bigendian_)
return field_iter->offset + 3;
else
return field_iter->offset + 0;
}
if (field_name == "a")
{
if (is_bigendian_)
return field_iter->offset + 0;
else
return field_iter->offset + 3;
}
} else
throw std::runtime_error("Field " + field_name + " does not exist");
}
return field_iter->offset;
}
}
}
#endif// SENSOR_MSGS_IMPL_POINT_CLOUD_ITERATOR_H

View File

@ -0,0 +1,302 @@
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2013, Open Source Robotics Foundation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Open Source Robotics Foundation nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H
#define SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H
#include <sensor_msgs/PointCloud2.h>
#include <cstdarg>
#include <string>
#include <vector>
/**
* \brief Tools for manipulating sensor_msgs
*
* This file provides two sets of utilities to modify and parse PointCloud2
* The first set allows you to conveniently set the fields by hand:
* <PRE>
* #include <sensor_msgs/point_cloud_iterator.h>
* // Create a PointCloud2
* sensor_msgs::PointCloud2 cloud_msg;
* // Fill some internals of the PoinCloud2 like the header/width/height ...
* cloud_msgs.height = 1; cloud_msgs.width = 4;
* // Set the point fields to xyzrgb and resize the vector with the following command
* // 4 is for the number of added fields. Each come in triplet: the name of the PointField,
* // the number of occurrences of the type in the PointField, the type of the PointField
* sensor_msgs::PointCloud2Modifier modifier(cloud_msg);
* modifier.setPointCloud2Fields(4, "x", 1, sensor_msgs::PointField::FLOAT32,
* "y", 1, sensor_msgs::PointField::FLOAT32,
* "z", 1, sensor_msgs::PointField::FLOAT32,
* "rgb", 1, sensor_msgs::PointField::FLOAT32);
* // For convenience and the xyz, rgb, rgba fields, you can also use the following overloaded function.
* // You have to be aware that the following function does add extra padding for backward compatibility though
* // so it is definitely the solution of choice for PointXYZ and PointXYZRGB
* // 2 is for the number of fields to add
* modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
* // You can then reserve / resize as usual
* modifier.resize(100);
* </PRE>
*
* The second set allow you to traverse your PointCloud using an iterator:
* <PRE>
* // Define some raw data we'll put in the PointCloud2
* float point_data[] = {1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0, 11.0, 12.0};
* uint8_t color_data[] = {40, 80, 120, 160, 200, 240, 20, 40, 60, 80, 100, 120};
* // Define the iterators. When doing so, you define the Field you would like to iterate upon and
* // the type of you would like returned: it is not necessary the type of the PointField as sometimes
* // you pack data in another type (e.g. 3 uchar + 1 uchar for RGB are packed in a float)
* sensor_msgs::PointCloud2Iterator<float> iter_x(cloud_msg, "x");
* sensor_msgs::PointCloud2Iterator<float> iter_y(cloud_msg, "y");
* sensor_msgs::PointCloud2Iterator<float> iter_z(cloud_msg, "z");
* // Even though the r,g,b,a fields do not exist (it's usually rgb, rgba), you can create iterators for
* // those: they will handle data packing for you (in little endian RGB is packed as *,R,G,B in a float
* // and RGBA as A,R,G,B)
* sensor_msgs::PointCloud2Iterator<uint8_t> iter_r(cloud_msg, "r");
* sensor_msgs::PointCloud2Iterator<uint8_t> iter_g(cloud_msg, "g");
* sensor_msgs::PointCloud2Iterator<uint8_t> iter_b(cloud_msg, "b");
* // Fill the PointCloud2
* for(size_t i=0; i<n_points; ++i, ++iter_x, ++iter_y, ++iter_z, ++iter_r, ++iter_g, ++iter_b) {
* *iter_x = point_data[3*i+0];
* *iter_y = point_data[3*i+1];
* *iter_z = point_data[3*i+2];
* *iter_r = color_data[3*i+0];
* *iter_g = color_data[3*i+1];
* *iter_b = color_data[3*i+2];
* }
* </PRE>
*/
namespace sensor_msgs
{
/**
* @brief Enables modifying a sensor_msgs::PointCloud2 like a container
*/
class PointCloud2Modifier
{
public:
/**
* @brief Default constructor
* @param cloud_msg The sensor_msgs::PointCloud2 to modify
*/
PointCloud2Modifier(PointCloud2& cloud_msg);
/**
* @return the number of T's in the original sensor_msgs::PointCloud2
*/
size_t size() const;
/**
* @param size The number of T's to reserve in the original sensor_msgs::PointCloud2 for
*/
void reserve(size_t size);
/**
* @param size The number of T's to change the size of the original sensor_msgs::PointCloud2 by
*/
void resize(size_t size);
/**
* @brief remove all T's from the original sensor_msgs::PointCloud2
*/
void clear();
/**
* @brief Function setting some fields in a PointCloud and adjusting the
* internals of the PointCloud2
* @param n_fields the number of fields to add. The fields are given as
* triplets: name of the field as char*, number of elements in the
* field, the datatype of the elements in the field
*
* E.g, you create your PointCloud2 message with XYZ/RGB as follows:
* <PRE>
* setPointCloud2Fields(cloud_msg, 4, "x", 1, sensor_msgs::PointField::FLOAT32,
* "y", 1, sensor_msgs::PointField::FLOAT32,
* "z", 1, sensor_msgs::PointField::FLOAT32,
* "rgb", 1, sensor_msgs::PointField::FLOAT32);
* </PRE>
* WARNING: THIS DOES NOT TAKE INTO ACCOUNT ANY PADDING AS DONE UNTIL HYDRO
* For simple usual cases, the overloaded setPointCloud2FieldsByString is what you want.
*/
void setPointCloud2Fields(int n_fields, ...);
/**
* @brief Function setting some fields in a PointCloud and adjusting the
* internals of the PointCloud2
* @param n_fields the number of fields to add. The fields are given as
* strings: "xyz" (3 floats), "rgb" (3 uchar stacked in a float),
* "rgba" (4 uchar stacked in a float)
* @return void
*
* WARNING: THIS FUNCTION DOES ADD ANY NECESSARY PADDING TRANSPARENTLY
*/
void setPointCloud2FieldsByString(int n_fields, ...);
protected:
/** A reference to the original sensor_msgs::PointCloud2 that we read */
PointCloud2& cloud_msg_;
};
namespace impl
{
/** Private base class for PointCloud2Iterator and PointCloud2ConstIterator
* T is the type of the value on which the child class will be templated
* TT is the type of the value to be retrieved (same as T except for constness)
* U is the type of the raw data in PointCloud2 (only uchar and const uchar are supported)
* C is the type of the pointcloud to intialize from (const or not)
* V is the derived class (yop, curiously recurring template pattern)
*/
template<typename T, typename TT, typename U, typename C, template <typename> class V>
class PointCloud2IteratorBase
{
public:
/**
*/
PointCloud2IteratorBase();
/**
* @param cloud_msg The PointCloud2 to iterate upon
* @param field_name The field to iterate upon
*/
PointCloud2IteratorBase(C &cloud_msg, const std::string &field_name);
/** Assignment operator
* @param iter the iterator to copy data from
* @return a reference to *this
*/
V<T>& operator =(const V<T>& iter);
/** Access the i th element starting at the current pointer (useful when a field has several elements of the same
* type)
* @param i
* @return a reference to the i^th value from the current position
*/
TT& operator [](size_t i) const;
/** Dereference the iterator. Equivalent to accessing it through [0]
* @return the value to which the iterator is pointing
*/
TT& operator *() const;
/** Increase the iterator to the next element
* @return a reference to the updated iterator
*/
V<T>& operator ++();
/** Basic pointer addition
* @param i the amount to increase the iterator by
* @return an iterator with an increased position
*/
V<T> operator +(int i);
/** Increase the iterator by a certain amount
* @return a reference to the updated iterator
*/
V<T>& operator +=(int i);
/** Compare to another iterator
* @return whether the current iterator points to a different address than the other one
*/
bool operator !=(const V<T>& iter) const;
/** Return the end iterator
* @return the end iterator (useful when performing normal iterator processing with ++)
*/
V<T> end() const;
private:
/** Common code to set the field of the PointCloud2
* @param cloud_msg the PointCloud2 to modify
* @param field_name the name of the field to iterate upon
* @return the offset at which the field is found
*/
int set_field(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name);
/** The "point_step" of the original cloud */
int point_step_;
/** The raw data in uchar* where the iterator is */
U* data_char_;
/** The cast data where the iterator is */
TT* data_;
/** The end() pointer of the iterator */
TT* data_end_;
/** Whether the fields are stored as bigendian */
bool is_bigendian_;
};
}
/**
* \brief Class that can iterate over a PointCloud2
*
* T type of the element being iterated upon
* E.g, you create your PointClou2 message as follows:
* <PRE>
* setPointCloud2FieldsByString(cloud_msg, 2, "xyz", "rgb");
* </PRE>
*
* For iterating over XYZ, you do :
* <PRE>
* sensor_msgs::PointCloud2Iterator<float> iter_x(cloud_msg, "x");
* </PRE>
* and then access X through iter_x[0] or *iter_x
* You could create an iterator for Y and Z too but as they are consecutive,
* you can just use iter_x[1] and iter_x[2]
*
* For iterating over RGB, you do:
* <PRE>
* sensor_msgs::PointCloud2Iterator<uint8_t> iter_rgb(cloud_msg, "rgb");
* </PRE>
* and then access R,G,B through iter_rgb[0], iter_rgb[1], iter_rgb[2]
*/
template<typename T>
class PointCloud2Iterator : public impl::PointCloud2IteratorBase<T, T, unsigned char, sensor_msgs::PointCloud2, PointCloud2Iterator>
{
public:
PointCloud2Iterator(sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) :
impl::PointCloud2IteratorBase<T, T, unsigned char, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2Iterator>::PointCloud2IteratorBase(cloud_msg, field_name) {}
};
/**
* \brief Same as a PointCloud2Iterator but for const data
*/
template<typename T>
class PointCloud2ConstIterator : public impl::PointCloud2IteratorBase<T, const T, const unsigned char, const sensor_msgs::PointCloud2, PointCloud2ConstIterator>
{
public:
PointCloud2ConstIterator(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) :
impl::PointCloud2IteratorBase<T, const T, const unsigned char, const sensor_msgs::PointCloud2, sensor_msgs::PointCloud2ConstIterator>::PointCloud2IteratorBase(cloud_msg, field_name) {}
};
}
#include <sensor_msgs/impl/point_cloud2_iterator.h>
#endif// SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H

View File

@ -0,0 +1,169 @@
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2010, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
* $Id$
*
*/
#ifndef SENSOR_MSGS_POINT_CLOUD_CONVERSION_H
#define SENSOR_MSGS_POINT_CLOUD_CONVERSION_H
#include <sensor_msgs/PointCloud.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/point_field_conversion.h>
/**
* \brief Convert between the old (sensor_msgs::PointCloud) and the new (sensor_msgs::PointCloud2) format.
* \author Radu Bogdan Rusu
*/
namespace sensor_msgs
{
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
/** \brief Get the index of a specified field (i.e., dimension/channel)
* \param points the the point cloud message
* \param field_name the string defining the field name
*/
static inline int getPointCloud2FieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
{
// Get the index we need
for (size_t d = 0; d < cloud.fields.size (); ++d)
if (cloud.fields[d].name == field_name)
return (d);
return (-1);
}
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
/** \brief Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message.
* \param input the message in the sensor_msgs::PointCloud format
* \param output the resultant message in the sensor_msgs::PointCloud2 format
*/
static inline bool convertPointCloudToPointCloud2 (const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)
{
output.header = input.header;
output.width = input.points.size ();
output.height = 1;
output.fields.resize (3 + input.channels.size ());
// Convert x/y/z to fields
output.fields[0].name = "x"; output.fields[1].name = "y"; output.fields[2].name = "z";
int offset = 0;
// All offsets are *4, as all field data types are float32
for (size_t d = 0; d < output.fields.size (); ++d, offset += 4)
{
output.fields[d].offset = offset;
output.fields[d].datatype = sensor_msgs::PointField::FLOAT32;
output.fields[d].count = 1;
}
output.point_step = offset;
output.row_step = output.point_step * output.width;
// Convert the remaining of the channels to fields
for (size_t d = 0; d < input.channels.size (); ++d)
output.fields[3 + d].name = input.channels[d].name;
output.data.resize (input.points.size () * output.point_step);
output.is_bigendian = false; // @todo ?
output.is_dense = false;
// Copy the data points
for (size_t cp = 0; cp < input.points.size (); ++cp)
{
memcpy (&output.data[cp * output.point_step + output.fields[0].offset], &input.points[cp].x, sizeof (float));
memcpy (&output.data[cp * output.point_step + output.fields[1].offset], &input.points[cp].y, sizeof (float));
memcpy (&output.data[cp * output.point_step + output.fields[2].offset], &input.points[cp].z, sizeof (float));
for (size_t d = 0; d < input.channels.size (); ++d)
{
if (input.channels[d].values.size() == input.points.size())
{
memcpy (&output.data[cp * output.point_step + output.fields[3 + d].offset], &input.channels[d].values[cp], sizeof (float));
}
}
}
return (true);
}
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
/** \brief Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message.
* \param input the message in the sensor_msgs::PointCloud2 format
* \param output the resultant message in the sensor_msgs::PointCloud format
*/
static inline bool convertPointCloud2ToPointCloud (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output)
{
output.header = input.header;
output.points.resize (input.width * input.height);
output.channels.resize (input.fields.size () - 3);
// Get the x/y/z field offsets
int x_idx = getPointCloud2FieldIndex (input, "x");
int y_idx = getPointCloud2FieldIndex (input, "y");
int z_idx = getPointCloud2FieldIndex (input, "z");
if (x_idx == -1 || y_idx == -1 || z_idx == -1)
{
std::cerr << "x/y/z coordinates not found! Cannot convert to sensor_msgs::PointCloud!" << std::endl;
return (false);
}
int x_offset = input.fields[x_idx].offset;
int y_offset = input.fields[y_idx].offset;
int z_offset = input.fields[z_idx].offset;
uint8_t x_datatype = input.fields[x_idx].datatype;
uint8_t y_datatype = input.fields[y_idx].datatype;
uint8_t z_datatype = input.fields[z_idx].datatype;
// Convert the fields to channels
int cur_c = 0;
for (size_t d = 0; d < input.fields.size (); ++d)
{
if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset)
continue;
output.channels[cur_c].name = input.fields[d].name;
output.channels[cur_c].values.resize (output.points.size ());
cur_c++;
}
// Copy the data points
for (size_t cp = 0; cp < output.points.size (); ++cp)
{
// Copy x/y/z
output.points[cp].x = sensor_msgs::readPointCloud2BufferValue<float>(&input.data[cp * input.point_step + x_offset], x_datatype);
output.points[cp].y = sensor_msgs::readPointCloud2BufferValue<float>(&input.data[cp * input.point_step + y_offset], y_datatype);
output.points[cp].z = sensor_msgs::readPointCloud2BufferValue<float>(&input.data[cp * input.point_step + z_offset], z_datatype);
// Copy the rest of the data
int cur_c = 0;
for (size_t d = 0; d < input.fields.size (); ++d)
{
if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset)
continue;
output.channels[cur_c++].values[cp] = sensor_msgs::readPointCloud2BufferValue<float>(&input.data[cp * input.point_step + input.fields[d].offset], input.fields[d].datatype);
}
}
return (true);
}
}
#endif// SENSOR_MSGS_POINT_CLOUD_CONVERSION_H

View File

@ -0,0 +1,180 @@
/*
* Software License Agreement (BSD License)
*
* Robot Operating System code by the University of Osnabrück
* Copyright (c) 2015, University of Osnabrück
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above
* copyright notice, this list of conditions and the following
* disclaimer.
*
* 2. Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
* TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
* OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
* OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
* ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*
*
* point_field_conversion.h
*
* Created on: 16.07.2015
* Authors: Sebastian Pütz <spuetz@uni-osnabrueck.de>
*/
#ifndef SENSOR_MSGS_POINT_FIELD_CONVERSION_H
#define SENSOR_MSGS_POINT_FIELD_CONVERSION_H
/**
* \brief This file provides a type to enum mapping for the different
* PointField types and methods to read and write in
* a PointCloud2 buffer for the different PointField types.
* \author Sebastian Pütz
*/
namespace sensor_msgs{
/*!
* \Enum to type mapping.
*/
template<int> struct pointFieldTypeAsType {};
template<> struct pointFieldTypeAsType<sensor_msgs::PointField::INT8> { typedef int8_t type; };
template<> struct pointFieldTypeAsType<sensor_msgs::PointField::UINT8> { typedef uint8_t type; };
template<> struct pointFieldTypeAsType<sensor_msgs::PointField::INT16> { typedef int16_t type; };
template<> struct pointFieldTypeAsType<sensor_msgs::PointField::UINT16> { typedef uint16_t type; };
template<> struct pointFieldTypeAsType<sensor_msgs::PointField::INT32> { typedef int32_t type; };
template<> struct pointFieldTypeAsType<sensor_msgs::PointField::UINT32> { typedef uint32_t type; };
template<> struct pointFieldTypeAsType<sensor_msgs::PointField::FLOAT32> { typedef float type; };
template<> struct pointFieldTypeAsType<sensor_msgs::PointField::FLOAT64> { typedef double type; };
/*!
* \Type to enum mapping.
*/
template<typename T> struct typeAsPointFieldType {};
template<> struct typeAsPointFieldType<int8_t> { static const uint8_t value = sensor_msgs::PointField::INT8; };
template<> struct typeAsPointFieldType<uint8_t> { static const uint8_t value = sensor_msgs::PointField::UINT8; };
template<> struct typeAsPointFieldType<int16_t> { static const uint8_t value = sensor_msgs::PointField::INT16; };
template<> struct typeAsPointFieldType<uint16_t> { static const uint8_t value = sensor_msgs::PointField::UINT16; };
template<> struct typeAsPointFieldType<int32_t> { static const uint8_t value = sensor_msgs::PointField::INT32; };
template<> struct typeAsPointFieldType<uint32_t> { static const uint8_t value = sensor_msgs::PointField::UINT32; };
template<> struct typeAsPointFieldType<float> { static const uint8_t value = sensor_msgs::PointField::FLOAT32; };
template<> struct typeAsPointFieldType<double> { static const uint8_t value = sensor_msgs::PointField::FLOAT64; };
/*!
* \Converts a value at the given pointer position, interpreted as the datatype
* specified by the given template argument point_field_type, to the given
* template type T and returns it.
* \param data_ptr pointer into the point cloud 2 buffer
* \tparam point_field_type sensor_msgs::PointField datatype value
* \tparam T return type
*/
template<int point_field_type, typename T>
inline T readPointCloud2BufferValue(const unsigned char* data_ptr){
typedef typename pointFieldTypeAsType<point_field_type>::type type;
return static_cast<T>(*(reinterpret_cast<type const *>(data_ptr)));
}
/*!
* \Converts a value at the given pointer position interpreted as the datatype
* specified by the given datatype parameter to the given template type and returns it.
* \param data_ptr pointer into the point cloud 2 buffer
* \param datatype sensor_msgs::PointField datatype value
* \tparam T return type
*/
template<typename T>
inline T readPointCloud2BufferValue(const unsigned char* data_ptr, const unsigned char datatype){
switch(datatype){
case sensor_msgs::PointField::INT8:
return readPointCloud2BufferValue<sensor_msgs::PointField::INT8, T>(data_ptr);
case sensor_msgs::PointField::UINT8:
return readPointCloud2BufferValue<sensor_msgs::PointField::UINT8, T>(data_ptr);
case sensor_msgs::PointField::INT16:
return readPointCloud2BufferValue<sensor_msgs::PointField::INT16, T>(data_ptr);
case sensor_msgs::PointField::UINT16:
return readPointCloud2BufferValue<sensor_msgs::PointField::UINT16, T>(data_ptr);
case sensor_msgs::PointField::INT32:
return readPointCloud2BufferValue<sensor_msgs::PointField::INT32, T>(data_ptr);
case sensor_msgs::PointField::UINT32:
return readPointCloud2BufferValue<sensor_msgs::PointField::UINT32, T>(data_ptr);
case sensor_msgs::PointField::FLOAT32:
return readPointCloud2BufferValue<sensor_msgs::PointField::FLOAT32, T>(data_ptr);
case sensor_msgs::PointField::FLOAT64:
return readPointCloud2BufferValue<sensor_msgs::PointField::FLOAT64, T>(data_ptr);
}
// This should never be reached, but return statement added to avoid compiler warning. (#84)
return T();
}
/*!
* \Inserts a given value at the given point position interpreted as the datatype
* specified by the template argument point_field_type.
* \param data_ptr pointer into the point cloud 2 buffer
* \param value the value to insert
* \tparam point_field_type sensor_msgs::PointField datatype value
* \tparam T type of the value to insert
*/
template<int point_field_type, typename T>
inline void writePointCloud2BufferValue(unsigned char* data_ptr, T value){
typedef typename pointFieldTypeAsType<point_field_type>::type type;
*(reinterpret_cast<type*>(data_ptr)) = static_cast<type>(value);
}
/*!
* \Inserts a given value at the given point position interpreted as the datatype
* specified by the given datatype parameter.
* \param data_ptr pointer into the point cloud 2 buffer
* \param datatype sensor_msgs::PointField datatype value
* \param value the value to insert
* \tparam T type of the value to insert
*/
template<typename T>
inline void writePointCloud2BufferValue(unsigned char* data_ptr, const unsigned char datatype, T value){
switch(datatype){
case sensor_msgs::PointField::INT8:
writePointCloud2BufferValue<sensor_msgs::PointField::INT8, T>(data_ptr, value);
break;
case sensor_msgs::PointField::UINT8:
writePointCloud2BufferValue<sensor_msgs::PointField::UINT8, T>(data_ptr, value);
break;
case sensor_msgs::PointField::INT16:
writePointCloud2BufferValue<sensor_msgs::PointField::INT16, T>(data_ptr, value);
break;
case sensor_msgs::PointField::UINT16:
writePointCloud2BufferValue<sensor_msgs::PointField::UINT16, T>(data_ptr, value);
break;
case sensor_msgs::PointField::INT32:
writePointCloud2BufferValue<sensor_msgs::PointField::INT32, T>(data_ptr, value);
break;
case sensor_msgs::PointField::UINT32:
writePointCloud2BufferValue<sensor_msgs::PointField::UINT32, T>(data_ptr, value);
break;
case sensor_msgs::PointField::FLOAT32:
writePointCloud2BufferValue<sensor_msgs::PointField::FLOAT32, T>(data_ptr, value);
break;
case sensor_msgs::PointField::FLOAT64:
writePointCloud2BufferValue<sensor_msgs::PointField::FLOAT64, T>(data_ptr, value);
break;
}
}
}
#endif /* point_field_conversion.h */

View File

@ -0,0 +1,372 @@
# This is the CMakeCache file.
# For build in directory: /home/duongtd/robotics_core/common_msgs/sensor_msgs/test
# It was generated by CMake: /usr/bin/cmake
# You can edit this file to change values found and used by cmake.
# If you do not want to change any of the values, simply exit the editor.
# If you do want to change a value, simply edit, save, and exit the editor.
# The syntax for the file is as follows:
# KEY:TYPE=VALUE
# KEY is the name of a variable in the cache.
# TYPE is a hint to GUIs for the type of VALUE, DO NOT EDIT TYPE!.
# VALUE is the current value for the KEY.
########################
# EXTERNAL cache entries
########################
//Path to a program.
CMAKE_ADDR2LINE:FILEPATH=/usr/bin/addr2line
//Path to a program.
CMAKE_AR:FILEPATH=/usr/bin/ar
//Choose the type of build, options are: None Debug Release RelWithDebInfo
// MinSizeRel ...
CMAKE_BUILD_TYPE:STRING=
//Enable/Disable color output during build.
CMAKE_COLOR_MAKEFILE:BOOL=ON
//CXX compiler
CMAKE_CXX_COMPILER:FILEPATH=/usr/bin/c++
//A wrapper around 'ar' adding the appropriate '--plugin' option
// for the GCC compiler
CMAKE_CXX_COMPILER_AR:FILEPATH=/usr/bin/gcc-ar-9
//A wrapper around 'ranlib' adding the appropriate '--plugin' option
// for the GCC compiler
CMAKE_CXX_COMPILER_RANLIB:FILEPATH=/usr/bin/gcc-ranlib-9
//Flags used by the CXX compiler during all build types.
CMAKE_CXX_FLAGS:STRING=
//Flags used by the CXX compiler during DEBUG builds.
CMAKE_CXX_FLAGS_DEBUG:STRING=-g
//Flags used by the CXX compiler during MINSIZEREL builds.
CMAKE_CXX_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG
//Flags used by the CXX compiler during RELEASE builds.
CMAKE_CXX_FLAGS_RELEASE:STRING=-O3 -DNDEBUG
//Flags used by the CXX compiler during RELWITHDEBINFO builds.
CMAKE_CXX_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG
//C compiler
CMAKE_C_COMPILER:FILEPATH=/usr/bin/cc
//A wrapper around 'ar' adding the appropriate '--plugin' option
// for the GCC compiler
CMAKE_C_COMPILER_AR:FILEPATH=/usr/bin/gcc-ar-9
//A wrapper around 'ranlib' adding the appropriate '--plugin' option
// for the GCC compiler
CMAKE_C_COMPILER_RANLIB:FILEPATH=/usr/bin/gcc-ranlib-9
//Flags used by the C compiler during all build types.
CMAKE_C_FLAGS:STRING=
//Flags used by the C compiler during DEBUG builds.
CMAKE_C_FLAGS_DEBUG:STRING=-g
//Flags used by the C compiler during MINSIZEREL builds.
CMAKE_C_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG
//Flags used by the C compiler during RELEASE builds.
CMAKE_C_FLAGS_RELEASE:STRING=-O3 -DNDEBUG
//Flags used by the C compiler during RELWITHDEBINFO builds.
CMAKE_C_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG
//Path to a program.
CMAKE_DLLTOOL:FILEPATH=CMAKE_DLLTOOL-NOTFOUND
//Flags used by the linker during all build types.
CMAKE_EXE_LINKER_FLAGS:STRING=
//Flags used by the linker during DEBUG builds.
CMAKE_EXE_LINKER_FLAGS_DEBUG:STRING=
//Flags used by the linker during MINSIZEREL builds.
CMAKE_EXE_LINKER_FLAGS_MINSIZEREL:STRING=
//Flags used by the linker during RELEASE builds.
CMAKE_EXE_LINKER_FLAGS_RELEASE:STRING=
//Flags used by the linker during RELWITHDEBINFO builds.
CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO:STRING=
//Enable/Disable output of compile commands during generation.
CMAKE_EXPORT_COMPILE_COMMANDS:BOOL=OFF
//Install path prefix, prepended onto install directories.
CMAKE_INSTALL_PREFIX:PATH=/usr/local
//Path to a program.
CMAKE_LINKER:FILEPATH=/usr/bin/ld
//Path to a program.
CMAKE_MAKE_PROGRAM:FILEPATH=/usr/bin/make
//Flags used by the linker during the creation of modules during
// all build types.
CMAKE_MODULE_LINKER_FLAGS:STRING=
//Flags used by the linker during the creation of modules during
// DEBUG builds.
CMAKE_MODULE_LINKER_FLAGS_DEBUG:STRING=
//Flags used by the linker during the creation of modules during
// MINSIZEREL builds.
CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL:STRING=
//Flags used by the linker during the creation of modules during
// RELEASE builds.
CMAKE_MODULE_LINKER_FLAGS_RELEASE:STRING=
//Flags used by the linker during the creation of modules during
// RELWITHDEBINFO builds.
CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO:STRING=
//Path to a program.
CMAKE_NM:FILEPATH=/usr/bin/nm
//Path to a program.
CMAKE_OBJCOPY:FILEPATH=/usr/bin/objcopy
//Path to a program.
CMAKE_OBJDUMP:FILEPATH=/usr/bin/objdump
//Value Computed by CMake
CMAKE_PROJECT_DESCRIPTION:STATIC=
//Value Computed by CMake
CMAKE_PROJECT_HOMEPAGE_URL:STATIC=
//Value Computed by CMake
CMAKE_PROJECT_NAME:STATIC=sensor_msgs
//Path to a program.
CMAKE_RANLIB:FILEPATH=/usr/bin/ranlib
//Path to a program.
CMAKE_READELF:FILEPATH=/usr/bin/readelf
//Flags used by the linker during the creation of shared libraries
// during all build types.
CMAKE_SHARED_LINKER_FLAGS:STRING=
//Flags used by the linker during the creation of shared libraries
// during DEBUG builds.
CMAKE_SHARED_LINKER_FLAGS_DEBUG:STRING=
//Flags used by the linker during the creation of shared libraries
// during MINSIZEREL builds.
CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL:STRING=
//Flags used by the linker during the creation of shared libraries
// during RELEASE builds.
CMAKE_SHARED_LINKER_FLAGS_RELEASE:STRING=
//Flags used by the linker during the creation of shared libraries
// during RELWITHDEBINFO builds.
CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO:STRING=
//If set, runtime paths are not added when installing shared libraries,
// but are added when building.
CMAKE_SKIP_INSTALL_RPATH:BOOL=NO
//If set, runtime paths are not added when using shared libraries.
CMAKE_SKIP_RPATH:BOOL=NO
//Flags used by the linker during the creation of static libraries
// during all build types.
CMAKE_STATIC_LINKER_FLAGS:STRING=
//Flags used by the linker during the creation of static libraries
// during DEBUG builds.
CMAKE_STATIC_LINKER_FLAGS_DEBUG:STRING=
//Flags used by the linker during the creation of static libraries
// during MINSIZEREL builds.
CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL:STRING=
//Flags used by the linker during the creation of static libraries
// during RELEASE builds.
CMAKE_STATIC_LINKER_FLAGS_RELEASE:STRING=
//Flags used by the linker during the creation of static libraries
// during RELWITHDEBINFO builds.
CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO:STRING=
//Path to a program.
CMAKE_STRIP:FILEPATH=/usr/bin/strip
//If this value is on, makefiles will be generated without the
// .SILENT directive, and all commands will be echoed to the console
// during the make. This is useful for debugging only. With Visual
// Studio IDE projects all commands are done without /nologo.
CMAKE_VERBOSE_MAKEFILE:BOOL=FALSE
//Value Computed by CMake
sensor_msgs_BINARY_DIR:STATIC=/home/duongtd/robotics_core/common_msgs/sensor_msgs/test
//Value Computed by CMake
sensor_msgs_SOURCE_DIR:STATIC=/home/duongtd/robotics_core/common_msgs/sensor_msgs
//Value Computed by CMake
std_msgs_BINARY_DIR:STATIC=/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/std_msgs_build
//Value Computed by CMake
std_msgs_SOURCE_DIR:STATIC=/home/duongtd/robotics_core/common_msgs/std_msgs
########################
# INTERNAL cache entries
########################
//ADVANCED property for variable: CMAKE_ADDR2LINE
CMAKE_ADDR2LINE-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_AR
CMAKE_AR-ADVANCED:INTERNAL=1
//This is the directory where this CMakeCache.txt was created
CMAKE_CACHEFILE_DIR:INTERNAL=/home/duongtd/robotics_core/common_msgs/sensor_msgs/test
//Major version of cmake used to create the current loaded cache
CMAKE_CACHE_MAJOR_VERSION:INTERNAL=3
//Minor version of cmake used to create the current loaded cache
CMAKE_CACHE_MINOR_VERSION:INTERNAL=16
//Patch version of cmake used to create the current loaded cache
CMAKE_CACHE_PATCH_VERSION:INTERNAL=3
//ADVANCED property for variable: CMAKE_COLOR_MAKEFILE
CMAKE_COLOR_MAKEFILE-ADVANCED:INTERNAL=1
//Path to CMake executable.
CMAKE_COMMAND:INTERNAL=/usr/bin/cmake
//Path to cpack program executable.
CMAKE_CPACK_COMMAND:INTERNAL=/usr/bin/cpack
//Path to ctest program executable.
CMAKE_CTEST_COMMAND:INTERNAL=/usr/bin/ctest
//ADVANCED property for variable: CMAKE_CXX_COMPILER
CMAKE_CXX_COMPILER-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_CXX_COMPILER_AR
CMAKE_CXX_COMPILER_AR-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_CXX_COMPILER_RANLIB
CMAKE_CXX_COMPILER_RANLIB-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_CXX_FLAGS
CMAKE_CXX_FLAGS-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_CXX_FLAGS_DEBUG
CMAKE_CXX_FLAGS_DEBUG-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_CXX_FLAGS_MINSIZEREL
CMAKE_CXX_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELEASE
CMAKE_CXX_FLAGS_RELEASE-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELWITHDEBINFO
CMAKE_CXX_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_C_COMPILER
CMAKE_C_COMPILER-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_C_COMPILER_AR
CMAKE_C_COMPILER_AR-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_C_COMPILER_RANLIB
CMAKE_C_COMPILER_RANLIB-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_C_FLAGS
CMAKE_C_FLAGS-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_C_FLAGS_DEBUG
CMAKE_C_FLAGS_DEBUG-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_C_FLAGS_MINSIZEREL
CMAKE_C_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_C_FLAGS_RELEASE
CMAKE_C_FLAGS_RELEASE-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_C_FLAGS_RELWITHDEBINFO
CMAKE_C_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_DLLTOOL
CMAKE_DLLTOOL-ADVANCED:INTERNAL=1
//Executable file format
CMAKE_EXECUTABLE_FORMAT:INTERNAL=ELF
//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS
CMAKE_EXE_LINKER_FLAGS-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_DEBUG
CMAKE_EXE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_MINSIZEREL
CMAKE_EXE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELEASE
CMAKE_EXE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO
CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_EXPORT_COMPILE_COMMANDS
CMAKE_EXPORT_COMPILE_COMMANDS-ADVANCED:INTERNAL=1
//Name of external makefile project generator.
CMAKE_EXTRA_GENERATOR:INTERNAL=
//Name of generator.
CMAKE_GENERATOR:INTERNAL=Unix Makefiles
//Generator instance identifier.
CMAKE_GENERATOR_INSTANCE:INTERNAL=
//Name of generator platform.
CMAKE_GENERATOR_PLATFORM:INTERNAL=
//Name of generator toolset.
CMAKE_GENERATOR_TOOLSET:INTERNAL=
//Source directory with the top level CMakeLists.txt file for this
// project
CMAKE_HOME_DIRECTORY:INTERNAL=/home/duongtd/robotics_core/common_msgs/sensor_msgs
//Install .so files without execute permission.
CMAKE_INSTALL_SO_NO_EXE:INTERNAL=1
//ADVANCED property for variable: CMAKE_LINKER
CMAKE_LINKER-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_MAKE_PROGRAM
CMAKE_MAKE_PROGRAM-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS
CMAKE_MODULE_LINKER_FLAGS-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_DEBUG
CMAKE_MODULE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL
CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELEASE
CMAKE_MODULE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO
CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_NM
CMAKE_NM-ADVANCED:INTERNAL=1
//number of local generators
CMAKE_NUMBER_OF_MAKEFILES:INTERNAL=2
//ADVANCED property for variable: CMAKE_OBJCOPY
CMAKE_OBJCOPY-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_OBJDUMP
CMAKE_OBJDUMP-ADVANCED:INTERNAL=1
//Platform information initialized
CMAKE_PLATFORM_INFO_INITIALIZED:INTERNAL=1
//ADVANCED property for variable: CMAKE_RANLIB
CMAKE_RANLIB-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_READELF
CMAKE_READELF-ADVANCED:INTERNAL=1
//Path to CMake installation.
CMAKE_ROOT:INTERNAL=/usr/share/cmake-3.16
//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS
CMAKE_SHARED_LINKER_FLAGS-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_DEBUG
CMAKE_SHARED_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL
CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELEASE
CMAKE_SHARED_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO
CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_SKIP_INSTALL_RPATH
CMAKE_SKIP_INSTALL_RPATH-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_SKIP_RPATH
CMAKE_SKIP_RPATH-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS
CMAKE_STATIC_LINKER_FLAGS-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_DEBUG
CMAKE_STATIC_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL
CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELEASE
CMAKE_STATIC_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO
CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1
//ADVANCED property for variable: CMAKE_STRIP
CMAKE_STRIP-ADVANCED:INTERNAL=1
//uname command
CMAKE_UNAME:INTERNAL=/usr/bin/uname
//ADVANCED property for variable: CMAKE_VERBOSE_MAKEFILE
CMAKE_VERBOSE_MAKEFILE-ADVANCED:INTERNAL=1

View File

@ -0,0 +1,76 @@
set(CMAKE_C_COMPILER "/usr/bin/cc")
set(CMAKE_C_COMPILER_ARG1 "")
set(CMAKE_C_COMPILER_ID "GNU")
set(CMAKE_C_COMPILER_VERSION "9.4.0")
set(CMAKE_C_COMPILER_VERSION_INTERNAL "")
set(CMAKE_C_COMPILER_WRAPPER "")
set(CMAKE_C_STANDARD_COMPUTED_DEFAULT "11")
set(CMAKE_C_COMPILE_FEATURES "c_std_90;c_function_prototypes;c_std_99;c_restrict;c_variadic_macros;c_std_11;c_static_assert")
set(CMAKE_C90_COMPILE_FEATURES "c_std_90;c_function_prototypes")
set(CMAKE_C99_COMPILE_FEATURES "c_std_99;c_restrict;c_variadic_macros")
set(CMAKE_C11_COMPILE_FEATURES "c_std_11;c_static_assert")
set(CMAKE_C_PLATFORM_ID "Linux")
set(CMAKE_C_SIMULATE_ID "")
set(CMAKE_C_COMPILER_FRONTEND_VARIANT "")
set(CMAKE_C_SIMULATE_VERSION "")
set(CMAKE_AR "/usr/bin/ar")
set(CMAKE_C_COMPILER_AR "/usr/bin/gcc-ar-9")
set(CMAKE_RANLIB "/usr/bin/ranlib")
set(CMAKE_C_COMPILER_RANLIB "/usr/bin/gcc-ranlib-9")
set(CMAKE_LINKER "/usr/bin/ld")
set(CMAKE_MT "")
set(CMAKE_COMPILER_IS_GNUCC 1)
set(CMAKE_C_COMPILER_LOADED 1)
set(CMAKE_C_COMPILER_WORKS TRUE)
set(CMAKE_C_ABI_COMPILED TRUE)
set(CMAKE_COMPILER_IS_MINGW )
set(CMAKE_COMPILER_IS_CYGWIN )
if(CMAKE_COMPILER_IS_CYGWIN)
set(CYGWIN 1)
set(UNIX 1)
endif()
set(CMAKE_C_COMPILER_ENV_VAR "CC")
if(CMAKE_COMPILER_IS_MINGW)
set(MINGW 1)
endif()
set(CMAKE_C_COMPILER_ID_RUN 1)
set(CMAKE_C_SOURCE_FILE_EXTENSIONS c;m)
set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC)
set(CMAKE_C_LINKER_PREFERENCE 10)
# Save compiler ABI information.
set(CMAKE_C_SIZEOF_DATA_PTR "8")
set(CMAKE_C_COMPILER_ABI "ELF")
set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu")
if(CMAKE_C_SIZEOF_DATA_PTR)
set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}")
endif()
if(CMAKE_C_COMPILER_ABI)
set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}")
endif()
if(CMAKE_C_LIBRARY_ARCHITECTURE)
set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu")
endif()
set(CMAKE_C_CL_SHOWINCLUDES_PREFIX "")
if(CMAKE_C_CL_SHOWINCLUDES_PREFIX)
set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_C_CL_SHOWINCLUDES_PREFIX}")
endif()
set(CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/9/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include")
set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "gcc;gcc_s;c;gcc;gcc_s")
set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/9;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib")
set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "")

View File

@ -0,0 +1,88 @@
set(CMAKE_CXX_COMPILER "/usr/bin/c++")
set(CMAKE_CXX_COMPILER_ARG1 "")
set(CMAKE_CXX_COMPILER_ID "GNU")
set(CMAKE_CXX_COMPILER_VERSION "9.4.0")
set(CMAKE_CXX_COMPILER_VERSION_INTERNAL "")
set(CMAKE_CXX_COMPILER_WRAPPER "")
set(CMAKE_CXX_STANDARD_COMPUTED_DEFAULT "14")
set(CMAKE_CXX_COMPILE_FEATURES "cxx_std_98;cxx_template_template_parameters;cxx_std_11;cxx_alias_templates;cxx_alignas;cxx_alignof;cxx_attributes;cxx_auto_type;cxx_constexpr;cxx_decltype;cxx_decltype_incomplete_return_types;cxx_default_function_template_args;cxx_defaulted_functions;cxx_defaulted_move_initializers;cxx_delegating_constructors;cxx_deleted_functions;cxx_enum_forward_declarations;cxx_explicit_conversions;cxx_extended_friend_declarations;cxx_extern_templates;cxx_final;cxx_func_identifier;cxx_generalized_initializers;cxx_inheriting_constructors;cxx_inline_namespaces;cxx_lambdas;cxx_local_type_template_args;cxx_long_long_type;cxx_noexcept;cxx_nonstatic_member_init;cxx_nullptr;cxx_override;cxx_range_for;cxx_raw_string_literals;cxx_reference_qualified_functions;cxx_right_angle_brackets;cxx_rvalue_references;cxx_sizeof_member;cxx_static_assert;cxx_strong_enums;cxx_thread_local;cxx_trailing_return_types;cxx_unicode_literals;cxx_uniform_initialization;cxx_unrestricted_unions;cxx_user_literals;cxx_variadic_macros;cxx_variadic_templates;cxx_std_14;cxx_aggregate_default_initializers;cxx_attribute_deprecated;cxx_binary_literals;cxx_contextual_conversions;cxx_decltype_auto;cxx_digit_separators;cxx_generic_lambdas;cxx_lambda_init_captures;cxx_relaxed_constexpr;cxx_return_type_deduction;cxx_variable_templates;cxx_std_17;cxx_std_20")
set(CMAKE_CXX98_COMPILE_FEATURES "cxx_std_98;cxx_template_template_parameters")
set(CMAKE_CXX11_COMPILE_FEATURES "cxx_std_11;cxx_alias_templates;cxx_alignas;cxx_alignof;cxx_attributes;cxx_auto_type;cxx_constexpr;cxx_decltype;cxx_decltype_incomplete_return_types;cxx_default_function_template_args;cxx_defaulted_functions;cxx_defaulted_move_initializers;cxx_delegating_constructors;cxx_deleted_functions;cxx_enum_forward_declarations;cxx_explicit_conversions;cxx_extended_friend_declarations;cxx_extern_templates;cxx_final;cxx_func_identifier;cxx_generalized_initializers;cxx_inheriting_constructors;cxx_inline_namespaces;cxx_lambdas;cxx_local_type_template_args;cxx_long_long_type;cxx_noexcept;cxx_nonstatic_member_init;cxx_nullptr;cxx_override;cxx_range_for;cxx_raw_string_literals;cxx_reference_qualified_functions;cxx_right_angle_brackets;cxx_rvalue_references;cxx_sizeof_member;cxx_static_assert;cxx_strong_enums;cxx_thread_local;cxx_trailing_return_types;cxx_unicode_literals;cxx_uniform_initialization;cxx_unrestricted_unions;cxx_user_literals;cxx_variadic_macros;cxx_variadic_templates")
set(CMAKE_CXX14_COMPILE_FEATURES "cxx_std_14;cxx_aggregate_default_initializers;cxx_attribute_deprecated;cxx_binary_literals;cxx_contextual_conversions;cxx_decltype_auto;cxx_digit_separators;cxx_generic_lambdas;cxx_lambda_init_captures;cxx_relaxed_constexpr;cxx_return_type_deduction;cxx_variable_templates")
set(CMAKE_CXX17_COMPILE_FEATURES "cxx_std_17")
set(CMAKE_CXX20_COMPILE_FEATURES "cxx_std_20")
set(CMAKE_CXX_PLATFORM_ID "Linux")
set(CMAKE_CXX_SIMULATE_ID "")
set(CMAKE_CXX_COMPILER_FRONTEND_VARIANT "")
set(CMAKE_CXX_SIMULATE_VERSION "")
set(CMAKE_AR "/usr/bin/ar")
set(CMAKE_CXX_COMPILER_AR "/usr/bin/gcc-ar-9")
set(CMAKE_RANLIB "/usr/bin/ranlib")
set(CMAKE_CXX_COMPILER_RANLIB "/usr/bin/gcc-ranlib-9")
set(CMAKE_LINKER "/usr/bin/ld")
set(CMAKE_MT "")
set(CMAKE_COMPILER_IS_GNUCXX 1)
set(CMAKE_CXX_COMPILER_LOADED 1)
set(CMAKE_CXX_COMPILER_WORKS TRUE)
set(CMAKE_CXX_ABI_COMPILED TRUE)
set(CMAKE_COMPILER_IS_MINGW )
set(CMAKE_COMPILER_IS_CYGWIN )
if(CMAKE_COMPILER_IS_CYGWIN)
set(CYGWIN 1)
set(UNIX 1)
endif()
set(CMAKE_CXX_COMPILER_ENV_VAR "CXX")
if(CMAKE_COMPILER_IS_MINGW)
set(MINGW 1)
endif()
set(CMAKE_CXX_COMPILER_ID_RUN 1)
set(CMAKE_CXX_SOURCE_FILE_EXTENSIONS C;M;c++;cc;cpp;cxx;m;mm;CPP)
set(CMAKE_CXX_IGNORE_EXTENSIONS inl;h;hpp;HPP;H;o;O;obj;OBJ;def;DEF;rc;RC)
foreach (lang C OBJC OBJCXX)
if (CMAKE_${lang}_COMPILER_ID_RUN)
foreach(extension IN LISTS CMAKE_${lang}_SOURCE_FILE_EXTENSIONS)
list(REMOVE_ITEM CMAKE_CXX_SOURCE_FILE_EXTENSIONS ${extension})
endforeach()
endif()
endforeach()
set(CMAKE_CXX_LINKER_PREFERENCE 30)
set(CMAKE_CXX_LINKER_PREFERENCE_PROPAGATES 1)
# Save compiler ABI information.
set(CMAKE_CXX_SIZEOF_DATA_PTR "8")
set(CMAKE_CXX_COMPILER_ABI "ELF")
set(CMAKE_CXX_LIBRARY_ARCHITECTURE "x86_64-linux-gnu")
if(CMAKE_CXX_SIZEOF_DATA_PTR)
set(CMAKE_SIZEOF_VOID_P "${CMAKE_CXX_SIZEOF_DATA_PTR}")
endif()
if(CMAKE_CXX_COMPILER_ABI)
set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_CXX_COMPILER_ABI}")
endif()
if(CMAKE_CXX_LIBRARY_ARCHITECTURE)
set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu")
endif()
set(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX "")
if(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX)
set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_CXX_CL_SHOWINCLUDES_PREFIX}")
endif()
set(CMAKE_CXX_IMPLICIT_INCLUDE_DIRECTORIES "/usr/include/c++/9;/usr/include/x86_64-linux-gnu/c++/9;/usr/include/c++/9/backward;/usr/lib/gcc/x86_64-linux-gnu/9/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include")
set(CMAKE_CXX_IMPLICIT_LINK_LIBRARIES "stdc++;m;gcc_s;gcc;c;gcc_s;gcc")
set(CMAKE_CXX_IMPLICIT_LINK_DIRECTORIES "/usr/lib/gcc/x86_64-linux-gnu/9;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib")
set(CMAKE_CXX_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "")

View File

@ -0,0 +1,15 @@
set(CMAKE_HOST_SYSTEM "Linux-5.15.0-139-generic")
set(CMAKE_HOST_SYSTEM_NAME "Linux")
set(CMAKE_HOST_SYSTEM_VERSION "5.15.0-139-generic")
set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64")
set(CMAKE_SYSTEM "Linux-5.15.0-139-generic")
set(CMAKE_SYSTEM_NAME "Linux")
set(CMAKE_SYSTEM_VERSION "5.15.0-139-generic")
set(CMAKE_SYSTEM_PROCESSOR "x86_64")
set(CMAKE_CROSSCOMPILING "FALSE")
set(CMAKE_SYSTEM_LOADED 1)

View File

@ -0,0 +1,671 @@
#ifdef __cplusplus
# error "A C++ compiler has been selected for C."
#endif
#if defined(__18CXX)
# define ID_VOID_MAIN
#endif
#if defined(__CLASSIC_C__)
/* cv-qualifiers did not exist in K&R C */
# define const
# define volatile
#endif
/* Version number components: V=Version, R=Revision, P=Patch
Version date components: YYYY=Year, MM=Month, DD=Day */
#if defined(__INTEL_COMPILER) || defined(__ICC)
# define COMPILER_ID "Intel"
# if defined(_MSC_VER)
# define SIMULATE_ID "MSVC"
# endif
# if defined(__GNUC__)
# define SIMULATE_ID "GNU"
# endif
/* __INTEL_COMPILER = VRP */
# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100)
# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10)
# if defined(__INTEL_COMPILER_UPDATE)
# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE)
# else
# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10)
# endif
# if defined(__INTEL_COMPILER_BUILD_DATE)
/* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */
# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE)
# endif
# if defined(_MSC_VER)
/* _MSC_VER = VVRR */
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
# endif
# if defined(__GNUC__)
# define SIMULATE_VERSION_MAJOR DEC(__GNUC__)
# elif defined(__GNUG__)
# define SIMULATE_VERSION_MAJOR DEC(__GNUG__)
# endif
# if defined(__GNUC_MINOR__)
# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__)
# endif
# if defined(__GNUC_PATCHLEVEL__)
# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
# endif
#elif defined(__PATHCC__)
# define COMPILER_ID "PathScale"
# define COMPILER_VERSION_MAJOR DEC(__PATHCC__)
# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__)
# if defined(__PATHCC_PATCHLEVEL__)
# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__)
# endif
#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__)
# define COMPILER_ID "Embarcadero"
# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF)
# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF)
# define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__ & 0xFFFF)
#elif defined(__BORLANDC__)
# define COMPILER_ID "Borland"
/* __BORLANDC__ = 0xVRR */
# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8)
# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF)
#elif defined(__WATCOMC__) && __WATCOMC__ < 1200
# define COMPILER_ID "Watcom"
/* __WATCOMC__ = VVRR */
# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100)
# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)
# if (__WATCOMC__ % 10) > 0
# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)
# endif
#elif defined(__WATCOMC__)
# define COMPILER_ID "OpenWatcom"
/* __WATCOMC__ = VVRP + 1100 */
# define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100)
# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)
# if (__WATCOMC__ % 10) > 0
# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)
# endif
#elif defined(__SUNPRO_C)
# define COMPILER_ID "SunPro"
# if __SUNPRO_C >= 0x5100
/* __SUNPRO_C = 0xVRRP */
# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>12)
# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xFF)
# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF)
# else
/* __SUNPRO_CC = 0xVRP */
# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>8)
# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xF)
# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF)
# endif
#elif defined(__HP_cc)
# define COMPILER_ID "HP"
/* __HP_cc = VVRRPP */
# define COMPILER_VERSION_MAJOR DEC(__HP_cc/10000)
# define COMPILER_VERSION_MINOR DEC(__HP_cc/100 % 100)
# define COMPILER_VERSION_PATCH DEC(__HP_cc % 100)
#elif defined(__DECC)
# define COMPILER_ID "Compaq"
/* __DECC_VER = VVRRTPPPP */
# define COMPILER_VERSION_MAJOR DEC(__DECC_VER/10000000)
# define COMPILER_VERSION_MINOR DEC(__DECC_VER/100000 % 100)
# define COMPILER_VERSION_PATCH DEC(__DECC_VER % 10000)
#elif defined(__IBMC__) && defined(__COMPILER_VER__)
# define COMPILER_ID "zOS"
/* __IBMC__ = VRP */
# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100)
# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10)
# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10)
#elif defined(__ibmxl__) && defined(__clang__)
# define COMPILER_ID "XLClang"
# define COMPILER_VERSION_MAJOR DEC(__ibmxl_version__)
# define COMPILER_VERSION_MINOR DEC(__ibmxl_release__)
# define COMPILER_VERSION_PATCH DEC(__ibmxl_modification__)
# define COMPILER_VERSION_TWEAK DEC(__ibmxl_ptf_fix_level__)
#elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ >= 800
# define COMPILER_ID "XL"
/* __IBMC__ = VRP */
# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100)
# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10)
# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10)
#elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ < 800
# define COMPILER_ID "VisualAge"
/* __IBMC__ = VRP */
# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100)
# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10)
# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10)
#elif defined(__PGI)
# define COMPILER_ID "PGI"
# define COMPILER_VERSION_MAJOR DEC(__PGIC__)
# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__)
# if defined(__PGIC_PATCHLEVEL__)
# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__)
# endif
#elif defined(_CRAYC)
# define COMPILER_ID "Cray"
# define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR)
# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR)
#elif defined(__TI_COMPILER_VERSION__)
# define COMPILER_ID "TI"
/* __TI_COMPILER_VERSION__ = VVVRRRPPP */
# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000)
# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000)
# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000)
#elif defined(__FUJITSU) || defined(__FCC_VERSION) || defined(__fcc_version)
# define COMPILER_ID "Fujitsu"
#elif defined(__ghs__)
# define COMPILER_ID "GHS"
/* __GHS_VERSION_NUMBER = VVVVRP */
# ifdef __GHS_VERSION_NUMBER
# define COMPILER_VERSION_MAJOR DEC(__GHS_VERSION_NUMBER / 100)
# define COMPILER_VERSION_MINOR DEC(__GHS_VERSION_NUMBER / 10 % 10)
# define COMPILER_VERSION_PATCH DEC(__GHS_VERSION_NUMBER % 10)
# endif
#elif defined(__TINYC__)
# define COMPILER_ID "TinyCC"
#elif defined(__BCC__)
# define COMPILER_ID "Bruce"
#elif defined(__SCO_VERSION__)
# define COMPILER_ID "SCO"
#elif defined(__ARMCC_VERSION) && !defined(__clang__)
# define COMPILER_ID "ARMCC"
#if __ARMCC_VERSION >= 1000000
/* __ARMCC_VERSION = VRRPPPP */
# define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000)
# define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100)
# define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000)
#else
/* __ARMCC_VERSION = VRPPPP */
# define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000)
# define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10)
# define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000)
#endif
#elif defined(__clang__) && defined(__apple_build_version__)
# define COMPILER_ID "AppleClang"
# if defined(_MSC_VER)
# define SIMULATE_ID "MSVC"
# endif
# define COMPILER_VERSION_MAJOR DEC(__clang_major__)
# define COMPILER_VERSION_MINOR DEC(__clang_minor__)
# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)
# if defined(_MSC_VER)
/* _MSC_VER = VVRR */
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
# endif
# define COMPILER_VERSION_TWEAK DEC(__apple_build_version__)
#elif defined(__clang__) && defined(__ARMCOMPILER_VERSION)
# define COMPILER_ID "ARMClang"
# define COMPILER_VERSION_MAJOR DEC(__ARMCOMPILER_VERSION/1000000)
# define COMPILER_VERSION_MINOR DEC(__ARMCOMPILER_VERSION/10000 % 100)
# define COMPILER_VERSION_PATCH DEC(__ARMCOMPILER_VERSION % 10000)
# define COMPILER_VERSION_INTERNAL DEC(__ARMCOMPILER_VERSION)
#elif defined(__clang__)
# define COMPILER_ID "Clang"
# if defined(_MSC_VER)
# define SIMULATE_ID "MSVC"
# endif
# define COMPILER_VERSION_MAJOR DEC(__clang_major__)
# define COMPILER_VERSION_MINOR DEC(__clang_minor__)
# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)
# if defined(_MSC_VER)
/* _MSC_VER = VVRR */
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
# endif
#elif defined(__GNUC__)
# define COMPILER_ID "GNU"
# define COMPILER_VERSION_MAJOR DEC(__GNUC__)
# if defined(__GNUC_MINOR__)
# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__)
# endif
# if defined(__GNUC_PATCHLEVEL__)
# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
# endif
#elif defined(_MSC_VER)
# define COMPILER_ID "MSVC"
/* _MSC_VER = VVRR */
# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100)
# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100)
# if defined(_MSC_FULL_VER)
# if _MSC_VER >= 1400
/* _MSC_FULL_VER = VVRRPPPPP */
# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000)
# else
/* _MSC_FULL_VER = VVRRPPPP */
# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000)
# endif
# endif
# if defined(_MSC_BUILD)
# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD)
# endif
#elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__)
# define COMPILER_ID "ADSP"
#if defined(__VISUALDSPVERSION__)
/* __VISUALDSPVERSION__ = 0xVVRRPP00 */
# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24)
# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF)
# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF)
#endif
#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC)
# define COMPILER_ID "IAR"
# if defined(__VER__) && defined(__ICCARM__)
# define COMPILER_VERSION_MAJOR DEC((__VER__) / 1000000)
# define COMPILER_VERSION_MINOR DEC(((__VER__) / 1000) % 1000)
# define COMPILER_VERSION_PATCH DEC((__VER__) % 1000)
# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__)
# elif defined(__VER__) && (defined(__ICCAVR__) || defined(__ICCRX__) || defined(__ICCRH850__) || defined(__ICCRL78__) || defined(__ICC430__) || defined(__ICCRISCV__) || defined(__ICCV850__) || defined(__ICC8051__))
# define COMPILER_VERSION_MAJOR DEC((__VER__) / 100)
# define COMPILER_VERSION_MINOR DEC((__VER__) - (((__VER__) / 100)*100))
# define COMPILER_VERSION_PATCH DEC(__SUBVERSION__)
# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__)
# endif
#elif defined(__SDCC_VERSION_MAJOR) || defined(SDCC)
# define COMPILER_ID "SDCC"
# if defined(__SDCC_VERSION_MAJOR)
# define COMPILER_VERSION_MAJOR DEC(__SDCC_VERSION_MAJOR)
# define COMPILER_VERSION_MINOR DEC(__SDCC_VERSION_MINOR)
# define COMPILER_VERSION_PATCH DEC(__SDCC_VERSION_PATCH)
# else
/* SDCC = VRP */
# define COMPILER_VERSION_MAJOR DEC(SDCC/100)
# define COMPILER_VERSION_MINOR DEC(SDCC/10 % 10)
# define COMPILER_VERSION_PATCH DEC(SDCC % 10)
# endif
/* These compilers are either not known or too old to define an
identification macro. Try to identify the platform and guess that
it is the native compiler. */
#elif defined(__hpux) || defined(__hpua)
# define COMPILER_ID "HP"
#else /* unknown compiler */
# define COMPILER_ID ""
#endif
/* Construct the string literal in pieces to prevent the source from
getting matched. Store it in a pointer rather than an array
because some compilers will just produce instructions to fill the
array rather than assigning a pointer to a static array. */
char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]";
#ifdef SIMULATE_ID
char const* info_simulate = "INFO" ":" "simulate[" SIMULATE_ID "]";
#endif
#ifdef __QNXNTO__
char const* qnxnto = "INFO" ":" "qnxnto[]";
#endif
#if defined(__CRAYXE) || defined(__CRAYXC)
char const *info_cray = "INFO" ":" "compiler_wrapper[CrayPrgEnv]";
#endif
#define STRINGIFY_HELPER(X) #X
#define STRINGIFY(X) STRINGIFY_HELPER(X)
/* Identify known platforms by name. */
#if defined(__linux) || defined(__linux__) || defined(linux)
# define PLATFORM_ID "Linux"
#elif defined(__CYGWIN__)
# define PLATFORM_ID "Cygwin"
#elif defined(__MINGW32__)
# define PLATFORM_ID "MinGW"
#elif defined(__APPLE__)
# define PLATFORM_ID "Darwin"
#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32)
# define PLATFORM_ID "Windows"
#elif defined(__FreeBSD__) || defined(__FreeBSD)
# define PLATFORM_ID "FreeBSD"
#elif defined(__NetBSD__) || defined(__NetBSD)
# define PLATFORM_ID "NetBSD"
#elif defined(__OpenBSD__) || defined(__OPENBSD)
# define PLATFORM_ID "OpenBSD"
#elif defined(__sun) || defined(sun)
# define PLATFORM_ID "SunOS"
#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__)
# define PLATFORM_ID "AIX"
#elif defined(__hpux) || defined(__hpux__)
# define PLATFORM_ID "HP-UX"
#elif defined(__HAIKU__)
# define PLATFORM_ID "Haiku"
#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS)
# define PLATFORM_ID "BeOS"
#elif defined(__QNX__) || defined(__QNXNTO__)
# define PLATFORM_ID "QNX"
#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__)
# define PLATFORM_ID "Tru64"
#elif defined(__riscos) || defined(__riscos__)
# define PLATFORM_ID "RISCos"
#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__)
# define PLATFORM_ID "SINIX"
#elif defined(__UNIX_SV__)
# define PLATFORM_ID "UNIX_SV"
#elif defined(__bsdos__)
# define PLATFORM_ID "BSDOS"
#elif defined(_MPRAS) || defined(MPRAS)
# define PLATFORM_ID "MP-RAS"
#elif defined(__osf) || defined(__osf__)
# define PLATFORM_ID "OSF1"
#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv)
# define PLATFORM_ID "SCO_SV"
#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX)
# define PLATFORM_ID "ULTRIX"
#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX)
# define PLATFORM_ID "Xenix"
#elif defined(__WATCOMC__)
# if defined(__LINUX__)
# define PLATFORM_ID "Linux"
# elif defined(__DOS__)
# define PLATFORM_ID "DOS"
# elif defined(__OS2__)
# define PLATFORM_ID "OS2"
# elif defined(__WINDOWS__)
# define PLATFORM_ID "Windows3x"
# else /* unknown platform */
# define PLATFORM_ID
# endif
#elif defined(__INTEGRITY)
# if defined(INT_178B)
# define PLATFORM_ID "Integrity178"
# else /* regular Integrity */
# define PLATFORM_ID "Integrity"
# endif
#else /* unknown platform */
# define PLATFORM_ID
#endif
/* For windows compilers MSVC and Intel we can determine
the architecture of the compiler being used. This is because
the compilers do not have flags that can change the architecture,
but rather depend on which compiler is being used
*/
#if defined(_WIN32) && defined(_MSC_VER)
# if defined(_M_IA64)
# define ARCHITECTURE_ID "IA64"
# elif defined(_M_X64) || defined(_M_AMD64)
# define ARCHITECTURE_ID "x64"
# elif defined(_M_IX86)
# define ARCHITECTURE_ID "X86"
# elif defined(_M_ARM64)
# define ARCHITECTURE_ID "ARM64"
# elif defined(_M_ARM)
# if _M_ARM == 4
# define ARCHITECTURE_ID "ARMV4I"
# elif _M_ARM == 5
# define ARCHITECTURE_ID "ARMV5I"
# else
# define ARCHITECTURE_ID "ARMV" STRINGIFY(_M_ARM)
# endif
# elif defined(_M_MIPS)
# define ARCHITECTURE_ID "MIPS"
# elif defined(_M_SH)
# define ARCHITECTURE_ID "SHx"
# else /* unknown architecture */
# define ARCHITECTURE_ID ""
# endif
#elif defined(__WATCOMC__)
# if defined(_M_I86)
# define ARCHITECTURE_ID "I86"
# elif defined(_M_IX86)
# define ARCHITECTURE_ID "X86"
# else /* unknown architecture */
# define ARCHITECTURE_ID ""
# endif
#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC)
# if defined(__ICCARM__)
# define ARCHITECTURE_ID "ARM"
# elif defined(__ICCRX__)
# define ARCHITECTURE_ID "RX"
# elif defined(__ICCRH850__)
# define ARCHITECTURE_ID "RH850"
# elif defined(__ICCRL78__)
# define ARCHITECTURE_ID "RL78"
# elif defined(__ICCRISCV__)
# define ARCHITECTURE_ID "RISCV"
# elif defined(__ICCAVR__)
# define ARCHITECTURE_ID "AVR"
# elif defined(__ICC430__)
# define ARCHITECTURE_ID "MSP430"
# elif defined(__ICCV850__)
# define ARCHITECTURE_ID "V850"
# elif defined(__ICC8051__)
# define ARCHITECTURE_ID "8051"
# else /* unknown architecture */
# define ARCHITECTURE_ID ""
# endif
#elif defined(__ghs__)
# if defined(__PPC64__)
# define ARCHITECTURE_ID "PPC64"
# elif defined(__ppc__)
# define ARCHITECTURE_ID "PPC"
# elif defined(__ARM__)
# define ARCHITECTURE_ID "ARM"
# elif defined(__x86_64__)
# define ARCHITECTURE_ID "x64"
# elif defined(__i386__)
# define ARCHITECTURE_ID "X86"
# else /* unknown architecture */
# define ARCHITECTURE_ID ""
# endif
#else
# define ARCHITECTURE_ID
#endif
/* Convert integer to decimal digit literals. */
#define DEC(n) \
('0' + (((n) / 10000000)%10)), \
('0' + (((n) / 1000000)%10)), \
('0' + (((n) / 100000)%10)), \
('0' + (((n) / 10000)%10)), \
('0' + (((n) / 1000)%10)), \
('0' + (((n) / 100)%10)), \
('0' + (((n) / 10)%10)), \
('0' + ((n) % 10))
/* Convert integer to hex digit literals. */
#define HEX(n) \
('0' + ((n)>>28 & 0xF)), \
('0' + ((n)>>24 & 0xF)), \
('0' + ((n)>>20 & 0xF)), \
('0' + ((n)>>16 & 0xF)), \
('0' + ((n)>>12 & 0xF)), \
('0' + ((n)>>8 & 0xF)), \
('0' + ((n)>>4 & 0xF)), \
('0' + ((n) & 0xF))
/* Construct a string literal encoding the version number components. */
#ifdef COMPILER_VERSION_MAJOR
char const info_version[] = {
'I', 'N', 'F', 'O', ':',
'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[',
COMPILER_VERSION_MAJOR,
# ifdef COMPILER_VERSION_MINOR
'.', COMPILER_VERSION_MINOR,
# ifdef COMPILER_VERSION_PATCH
'.', COMPILER_VERSION_PATCH,
# ifdef COMPILER_VERSION_TWEAK
'.', COMPILER_VERSION_TWEAK,
# endif
# endif
# endif
']','\0'};
#endif
/* Construct a string literal encoding the internal version number. */
#ifdef COMPILER_VERSION_INTERNAL
char const info_version_internal[] = {
'I', 'N', 'F', 'O', ':',
'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','_',
'i','n','t','e','r','n','a','l','[',
COMPILER_VERSION_INTERNAL,']','\0'};
#endif
/* Construct a string literal encoding the version number components. */
#ifdef SIMULATE_VERSION_MAJOR
char const info_simulate_version[] = {
'I', 'N', 'F', 'O', ':',
's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[',
SIMULATE_VERSION_MAJOR,
# ifdef SIMULATE_VERSION_MINOR
'.', SIMULATE_VERSION_MINOR,
# ifdef SIMULATE_VERSION_PATCH
'.', SIMULATE_VERSION_PATCH,
# ifdef SIMULATE_VERSION_TWEAK
'.', SIMULATE_VERSION_TWEAK,
# endif
# endif
# endif
']','\0'};
#endif
/* Construct the string literal in pieces to prevent the source from
getting matched. Store it in a pointer rather than an array
because some compilers will just produce instructions to fill the
array rather than assigning a pointer to a static array. */
char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]";
char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]";
#if !defined(__STDC__)
# if (defined(_MSC_VER) && !defined(__clang__)) \
|| (defined(__ibmxl__) || defined(__IBMC__))
# define C_DIALECT "90"
# else
# define C_DIALECT
# endif
#elif __STDC_VERSION__ >= 201000L
# define C_DIALECT "11"
#elif __STDC_VERSION__ >= 199901L
# define C_DIALECT "99"
#else
# define C_DIALECT "90"
#endif
const char* info_language_dialect_default =
"INFO" ":" "dialect_default[" C_DIALECT "]";
/*--------------------------------------------------------------------------*/
#ifdef ID_VOID_MAIN
void main() {}
#else
# if defined(__CLASSIC_C__)
int main(argc, argv) int argc; char *argv[];
# else
int main(int argc, char* argv[])
# endif
{
int require = 0;
require += info_compiler[argc];
require += info_platform[argc];
require += info_arch[argc];
#ifdef COMPILER_VERSION_MAJOR
require += info_version[argc];
#endif
#ifdef COMPILER_VERSION_INTERNAL
require += info_version_internal[argc];
#endif
#ifdef SIMULATE_ID
require += info_simulate[argc];
#endif
#ifdef SIMULATE_VERSION_MAJOR
require += info_simulate_version[argc];
#endif
#if defined(__CRAYXE) || defined(__CRAYXC)
require += info_cray[argc];
#endif
require += info_language_dialect_default[argc];
(void)argv;
return require;
}
#endif

Binary file not shown.

View File

@ -0,0 +1,660 @@
/* This source file must have a .cpp extension so that all C++ compilers
recognize the extension without flags. Borland does not know .cxx for
example. */
#ifndef __cplusplus
# error "A C compiler has been selected for C++."
#endif
/* Version number components: V=Version, R=Revision, P=Patch
Version date components: YYYY=Year, MM=Month, DD=Day */
#if defined(__COMO__)
# define COMPILER_ID "Comeau"
/* __COMO_VERSION__ = VRR */
# define COMPILER_VERSION_MAJOR DEC(__COMO_VERSION__ / 100)
# define COMPILER_VERSION_MINOR DEC(__COMO_VERSION__ % 100)
#elif defined(__INTEL_COMPILER) || defined(__ICC)
# define COMPILER_ID "Intel"
# if defined(_MSC_VER)
# define SIMULATE_ID "MSVC"
# endif
# if defined(__GNUC__)
# define SIMULATE_ID "GNU"
# endif
/* __INTEL_COMPILER = VRP */
# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100)
# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10)
# if defined(__INTEL_COMPILER_UPDATE)
# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE)
# else
# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10)
# endif
# if defined(__INTEL_COMPILER_BUILD_DATE)
/* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */
# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE)
# endif
# if defined(_MSC_VER)
/* _MSC_VER = VVRR */
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
# endif
# if defined(__GNUC__)
# define SIMULATE_VERSION_MAJOR DEC(__GNUC__)
# elif defined(__GNUG__)
# define SIMULATE_VERSION_MAJOR DEC(__GNUG__)
# endif
# if defined(__GNUC_MINOR__)
# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__)
# endif
# if defined(__GNUC_PATCHLEVEL__)
# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
# endif
#elif defined(__PATHCC__)
# define COMPILER_ID "PathScale"
# define COMPILER_VERSION_MAJOR DEC(__PATHCC__)
# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__)
# if defined(__PATHCC_PATCHLEVEL__)
# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__)
# endif
#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__)
# define COMPILER_ID "Embarcadero"
# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF)
# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF)
# define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__ & 0xFFFF)
#elif defined(__BORLANDC__)
# define COMPILER_ID "Borland"
/* __BORLANDC__ = 0xVRR */
# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8)
# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF)
#elif defined(__WATCOMC__) && __WATCOMC__ < 1200
# define COMPILER_ID "Watcom"
/* __WATCOMC__ = VVRR */
# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100)
# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)
# if (__WATCOMC__ % 10) > 0
# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)
# endif
#elif defined(__WATCOMC__)
# define COMPILER_ID "OpenWatcom"
/* __WATCOMC__ = VVRP + 1100 */
# define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100)
# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)
# if (__WATCOMC__ % 10) > 0
# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)
# endif
#elif defined(__SUNPRO_CC)
# define COMPILER_ID "SunPro"
# if __SUNPRO_CC >= 0x5100
/* __SUNPRO_CC = 0xVRRP */
# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>12)
# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xFF)
# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF)
# else
/* __SUNPRO_CC = 0xVRP */
# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>8)
# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xF)
# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF)
# endif
#elif defined(__HP_aCC)
# define COMPILER_ID "HP"
/* __HP_aCC = VVRRPP */
# define COMPILER_VERSION_MAJOR DEC(__HP_aCC/10000)
# define COMPILER_VERSION_MINOR DEC(__HP_aCC/100 % 100)
# define COMPILER_VERSION_PATCH DEC(__HP_aCC % 100)
#elif defined(__DECCXX)
# define COMPILER_ID "Compaq"
/* __DECCXX_VER = VVRRTPPPP */
# define COMPILER_VERSION_MAJOR DEC(__DECCXX_VER/10000000)
# define COMPILER_VERSION_MINOR DEC(__DECCXX_VER/100000 % 100)
# define COMPILER_VERSION_PATCH DEC(__DECCXX_VER % 10000)
#elif defined(__IBMCPP__) && defined(__COMPILER_VER__)
# define COMPILER_ID "zOS"
/* __IBMCPP__ = VRP */
# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100)
# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10)
# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10)
#elif defined(__ibmxl__) && defined(__clang__)
# define COMPILER_ID "XLClang"
# define COMPILER_VERSION_MAJOR DEC(__ibmxl_version__)
# define COMPILER_VERSION_MINOR DEC(__ibmxl_release__)
# define COMPILER_VERSION_PATCH DEC(__ibmxl_modification__)
# define COMPILER_VERSION_TWEAK DEC(__ibmxl_ptf_fix_level__)
#elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ >= 800
# define COMPILER_ID "XL"
/* __IBMCPP__ = VRP */
# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100)
# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10)
# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10)
#elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ < 800
# define COMPILER_ID "VisualAge"
/* __IBMCPP__ = VRP */
# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100)
# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10)
# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10)
#elif defined(__PGI)
# define COMPILER_ID "PGI"
# define COMPILER_VERSION_MAJOR DEC(__PGIC__)
# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__)
# if defined(__PGIC_PATCHLEVEL__)
# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__)
# endif
#elif defined(_CRAYC)
# define COMPILER_ID "Cray"
# define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR)
# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR)
#elif defined(__TI_COMPILER_VERSION__)
# define COMPILER_ID "TI"
/* __TI_COMPILER_VERSION__ = VVVRRRPPP */
# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000)
# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000)
# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000)
#elif defined(__FUJITSU) || defined(__FCC_VERSION) || defined(__fcc_version)
# define COMPILER_ID "Fujitsu"
#elif defined(__ghs__)
# define COMPILER_ID "GHS"
/* __GHS_VERSION_NUMBER = VVVVRP */
# ifdef __GHS_VERSION_NUMBER
# define COMPILER_VERSION_MAJOR DEC(__GHS_VERSION_NUMBER / 100)
# define COMPILER_VERSION_MINOR DEC(__GHS_VERSION_NUMBER / 10 % 10)
# define COMPILER_VERSION_PATCH DEC(__GHS_VERSION_NUMBER % 10)
# endif
#elif defined(__SCO_VERSION__)
# define COMPILER_ID "SCO"
#elif defined(__ARMCC_VERSION) && !defined(__clang__)
# define COMPILER_ID "ARMCC"
#if __ARMCC_VERSION >= 1000000
/* __ARMCC_VERSION = VRRPPPP */
# define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000)
# define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100)
# define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000)
#else
/* __ARMCC_VERSION = VRPPPP */
# define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000)
# define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10)
# define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000)
#endif
#elif defined(__clang__) && defined(__apple_build_version__)
# define COMPILER_ID "AppleClang"
# if defined(_MSC_VER)
# define SIMULATE_ID "MSVC"
# endif
# define COMPILER_VERSION_MAJOR DEC(__clang_major__)
# define COMPILER_VERSION_MINOR DEC(__clang_minor__)
# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)
# if defined(_MSC_VER)
/* _MSC_VER = VVRR */
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
# endif
# define COMPILER_VERSION_TWEAK DEC(__apple_build_version__)
#elif defined(__clang__) && defined(__ARMCOMPILER_VERSION)
# define COMPILER_ID "ARMClang"
# define COMPILER_VERSION_MAJOR DEC(__ARMCOMPILER_VERSION/1000000)
# define COMPILER_VERSION_MINOR DEC(__ARMCOMPILER_VERSION/10000 % 100)
# define COMPILER_VERSION_PATCH DEC(__ARMCOMPILER_VERSION % 10000)
# define COMPILER_VERSION_INTERNAL DEC(__ARMCOMPILER_VERSION)
#elif defined(__clang__)
# define COMPILER_ID "Clang"
# if defined(_MSC_VER)
# define SIMULATE_ID "MSVC"
# endif
# define COMPILER_VERSION_MAJOR DEC(__clang_major__)
# define COMPILER_VERSION_MINOR DEC(__clang_minor__)
# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)
# if defined(_MSC_VER)
/* _MSC_VER = VVRR */
# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)
# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)
# endif
#elif defined(__GNUC__) || defined(__GNUG__)
# define COMPILER_ID "GNU"
# if defined(__GNUC__)
# define COMPILER_VERSION_MAJOR DEC(__GNUC__)
# else
# define COMPILER_VERSION_MAJOR DEC(__GNUG__)
# endif
# if defined(__GNUC_MINOR__)
# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__)
# endif
# if defined(__GNUC_PATCHLEVEL__)
# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)
# endif
#elif defined(_MSC_VER)
# define COMPILER_ID "MSVC"
/* _MSC_VER = VVRR */
# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100)
# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100)
# if defined(_MSC_FULL_VER)
# if _MSC_VER >= 1400
/* _MSC_FULL_VER = VVRRPPPPP */
# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000)
# else
/* _MSC_FULL_VER = VVRRPPPP */
# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000)
# endif
# endif
# if defined(_MSC_BUILD)
# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD)
# endif
#elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__)
# define COMPILER_ID "ADSP"
#if defined(__VISUALDSPVERSION__)
/* __VISUALDSPVERSION__ = 0xVVRRPP00 */
# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24)
# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF)
# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF)
#endif
#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC)
# define COMPILER_ID "IAR"
# if defined(__VER__) && defined(__ICCARM__)
# define COMPILER_VERSION_MAJOR DEC((__VER__) / 1000000)
# define COMPILER_VERSION_MINOR DEC(((__VER__) / 1000) % 1000)
# define COMPILER_VERSION_PATCH DEC((__VER__) % 1000)
# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__)
# elif defined(__VER__) && (defined(__ICCAVR__) || defined(__ICCRX__) || defined(__ICCRH850__) || defined(__ICCRL78__) || defined(__ICC430__) || defined(__ICCRISCV__) || defined(__ICCV850__) || defined(__ICC8051__))
# define COMPILER_VERSION_MAJOR DEC((__VER__) / 100)
# define COMPILER_VERSION_MINOR DEC((__VER__) - (((__VER__) / 100)*100))
# define COMPILER_VERSION_PATCH DEC(__SUBVERSION__)
# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__)
# endif
/* These compilers are either not known or too old to define an
identification macro. Try to identify the platform and guess that
it is the native compiler. */
#elif defined(__hpux) || defined(__hpua)
# define COMPILER_ID "HP"
#else /* unknown compiler */
# define COMPILER_ID ""
#endif
/* Construct the string literal in pieces to prevent the source from
getting matched. Store it in a pointer rather than an array
because some compilers will just produce instructions to fill the
array rather than assigning a pointer to a static array. */
char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]";
#ifdef SIMULATE_ID
char const* info_simulate = "INFO" ":" "simulate[" SIMULATE_ID "]";
#endif
#ifdef __QNXNTO__
char const* qnxnto = "INFO" ":" "qnxnto[]";
#endif
#if defined(__CRAYXE) || defined(__CRAYXC)
char const *info_cray = "INFO" ":" "compiler_wrapper[CrayPrgEnv]";
#endif
#define STRINGIFY_HELPER(X) #X
#define STRINGIFY(X) STRINGIFY_HELPER(X)
/* Identify known platforms by name. */
#if defined(__linux) || defined(__linux__) || defined(linux)
# define PLATFORM_ID "Linux"
#elif defined(__CYGWIN__)
# define PLATFORM_ID "Cygwin"
#elif defined(__MINGW32__)
# define PLATFORM_ID "MinGW"
#elif defined(__APPLE__)
# define PLATFORM_ID "Darwin"
#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32)
# define PLATFORM_ID "Windows"
#elif defined(__FreeBSD__) || defined(__FreeBSD)
# define PLATFORM_ID "FreeBSD"
#elif defined(__NetBSD__) || defined(__NetBSD)
# define PLATFORM_ID "NetBSD"
#elif defined(__OpenBSD__) || defined(__OPENBSD)
# define PLATFORM_ID "OpenBSD"
#elif defined(__sun) || defined(sun)
# define PLATFORM_ID "SunOS"
#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__)
# define PLATFORM_ID "AIX"
#elif defined(__hpux) || defined(__hpux__)
# define PLATFORM_ID "HP-UX"
#elif defined(__HAIKU__)
# define PLATFORM_ID "Haiku"
#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS)
# define PLATFORM_ID "BeOS"
#elif defined(__QNX__) || defined(__QNXNTO__)
# define PLATFORM_ID "QNX"
#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__)
# define PLATFORM_ID "Tru64"
#elif defined(__riscos) || defined(__riscos__)
# define PLATFORM_ID "RISCos"
#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__)
# define PLATFORM_ID "SINIX"
#elif defined(__UNIX_SV__)
# define PLATFORM_ID "UNIX_SV"
#elif defined(__bsdos__)
# define PLATFORM_ID "BSDOS"
#elif defined(_MPRAS) || defined(MPRAS)
# define PLATFORM_ID "MP-RAS"
#elif defined(__osf) || defined(__osf__)
# define PLATFORM_ID "OSF1"
#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv)
# define PLATFORM_ID "SCO_SV"
#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX)
# define PLATFORM_ID "ULTRIX"
#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX)
# define PLATFORM_ID "Xenix"
#elif defined(__WATCOMC__)
# if defined(__LINUX__)
# define PLATFORM_ID "Linux"
# elif defined(__DOS__)
# define PLATFORM_ID "DOS"
# elif defined(__OS2__)
# define PLATFORM_ID "OS2"
# elif defined(__WINDOWS__)
# define PLATFORM_ID "Windows3x"
# else /* unknown platform */
# define PLATFORM_ID
# endif
#elif defined(__INTEGRITY)
# if defined(INT_178B)
# define PLATFORM_ID "Integrity178"
# else /* regular Integrity */
# define PLATFORM_ID "Integrity"
# endif
#else /* unknown platform */
# define PLATFORM_ID
#endif
/* For windows compilers MSVC and Intel we can determine
the architecture of the compiler being used. This is because
the compilers do not have flags that can change the architecture,
but rather depend on which compiler is being used
*/
#if defined(_WIN32) && defined(_MSC_VER)
# if defined(_M_IA64)
# define ARCHITECTURE_ID "IA64"
# elif defined(_M_X64) || defined(_M_AMD64)
# define ARCHITECTURE_ID "x64"
# elif defined(_M_IX86)
# define ARCHITECTURE_ID "X86"
# elif defined(_M_ARM64)
# define ARCHITECTURE_ID "ARM64"
# elif defined(_M_ARM)
# if _M_ARM == 4
# define ARCHITECTURE_ID "ARMV4I"
# elif _M_ARM == 5
# define ARCHITECTURE_ID "ARMV5I"
# else
# define ARCHITECTURE_ID "ARMV" STRINGIFY(_M_ARM)
# endif
# elif defined(_M_MIPS)
# define ARCHITECTURE_ID "MIPS"
# elif defined(_M_SH)
# define ARCHITECTURE_ID "SHx"
# else /* unknown architecture */
# define ARCHITECTURE_ID ""
# endif
#elif defined(__WATCOMC__)
# if defined(_M_I86)
# define ARCHITECTURE_ID "I86"
# elif defined(_M_IX86)
# define ARCHITECTURE_ID "X86"
# else /* unknown architecture */
# define ARCHITECTURE_ID ""
# endif
#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC)
# if defined(__ICCARM__)
# define ARCHITECTURE_ID "ARM"
# elif defined(__ICCRX__)
# define ARCHITECTURE_ID "RX"
# elif defined(__ICCRH850__)
# define ARCHITECTURE_ID "RH850"
# elif defined(__ICCRL78__)
# define ARCHITECTURE_ID "RL78"
# elif defined(__ICCRISCV__)
# define ARCHITECTURE_ID "RISCV"
# elif defined(__ICCAVR__)
# define ARCHITECTURE_ID "AVR"
# elif defined(__ICC430__)
# define ARCHITECTURE_ID "MSP430"
# elif defined(__ICCV850__)
# define ARCHITECTURE_ID "V850"
# elif defined(__ICC8051__)
# define ARCHITECTURE_ID "8051"
# else /* unknown architecture */
# define ARCHITECTURE_ID ""
# endif
#elif defined(__ghs__)
# if defined(__PPC64__)
# define ARCHITECTURE_ID "PPC64"
# elif defined(__ppc__)
# define ARCHITECTURE_ID "PPC"
# elif defined(__ARM__)
# define ARCHITECTURE_ID "ARM"
# elif defined(__x86_64__)
# define ARCHITECTURE_ID "x64"
# elif defined(__i386__)
# define ARCHITECTURE_ID "X86"
# else /* unknown architecture */
# define ARCHITECTURE_ID ""
# endif
#else
# define ARCHITECTURE_ID
#endif
/* Convert integer to decimal digit literals. */
#define DEC(n) \
('0' + (((n) / 10000000)%10)), \
('0' + (((n) / 1000000)%10)), \
('0' + (((n) / 100000)%10)), \
('0' + (((n) / 10000)%10)), \
('0' + (((n) / 1000)%10)), \
('0' + (((n) / 100)%10)), \
('0' + (((n) / 10)%10)), \
('0' + ((n) % 10))
/* Convert integer to hex digit literals. */
#define HEX(n) \
('0' + ((n)>>28 & 0xF)), \
('0' + ((n)>>24 & 0xF)), \
('0' + ((n)>>20 & 0xF)), \
('0' + ((n)>>16 & 0xF)), \
('0' + ((n)>>12 & 0xF)), \
('0' + ((n)>>8 & 0xF)), \
('0' + ((n)>>4 & 0xF)), \
('0' + ((n) & 0xF))
/* Construct a string literal encoding the version number components. */
#ifdef COMPILER_VERSION_MAJOR
char const info_version[] = {
'I', 'N', 'F', 'O', ':',
'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[',
COMPILER_VERSION_MAJOR,
# ifdef COMPILER_VERSION_MINOR
'.', COMPILER_VERSION_MINOR,
# ifdef COMPILER_VERSION_PATCH
'.', COMPILER_VERSION_PATCH,
# ifdef COMPILER_VERSION_TWEAK
'.', COMPILER_VERSION_TWEAK,
# endif
# endif
# endif
']','\0'};
#endif
/* Construct a string literal encoding the internal version number. */
#ifdef COMPILER_VERSION_INTERNAL
char const info_version_internal[] = {
'I', 'N', 'F', 'O', ':',
'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','_',
'i','n','t','e','r','n','a','l','[',
COMPILER_VERSION_INTERNAL,']','\0'};
#endif
/* Construct a string literal encoding the version number components. */
#ifdef SIMULATE_VERSION_MAJOR
char const info_simulate_version[] = {
'I', 'N', 'F', 'O', ':',
's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[',
SIMULATE_VERSION_MAJOR,
# ifdef SIMULATE_VERSION_MINOR
'.', SIMULATE_VERSION_MINOR,
# ifdef SIMULATE_VERSION_PATCH
'.', SIMULATE_VERSION_PATCH,
# ifdef SIMULATE_VERSION_TWEAK
'.', SIMULATE_VERSION_TWEAK,
# endif
# endif
# endif
']','\0'};
#endif
/* Construct the string literal in pieces to prevent the source from
getting matched. Store it in a pointer rather than an array
because some compilers will just produce instructions to fill the
array rather than assigning a pointer to a static array. */
char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]";
char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]";
#if defined(__INTEL_COMPILER) && defined(_MSVC_LANG) && _MSVC_LANG < 201403L
# if defined(__INTEL_CXX11_MODE__)
# if defined(__cpp_aggregate_nsdmi)
# define CXX_STD 201402L
# else
# define CXX_STD 201103L
# endif
# else
# define CXX_STD 199711L
# endif
#elif defined(_MSC_VER) && defined(_MSVC_LANG)
# define CXX_STD _MSVC_LANG
#else
# define CXX_STD __cplusplus
#endif
const char* info_language_dialect_default = "INFO" ":" "dialect_default["
#if CXX_STD > 201703L
"20"
#elif CXX_STD >= 201703L
"17"
#elif CXX_STD >= 201402L
"14"
#elif CXX_STD >= 201103L
"11"
#else
"98"
#endif
"]";
/*--------------------------------------------------------------------------*/
int main(int argc, char* argv[])
{
int require = 0;
require += info_compiler[argc];
require += info_platform[argc];
#ifdef COMPILER_VERSION_MAJOR
require += info_version[argc];
#endif
#ifdef COMPILER_VERSION_INTERNAL
require += info_version_internal[argc];
#endif
#ifdef SIMULATE_ID
require += info_simulate[argc];
#endif
#ifdef SIMULATE_VERSION_MAJOR
require += info_simulate_version[argc];
#endif
#if defined(__CRAYXE) || defined(__CRAYXC)
require += info_cray[argc];
#endif
require += info_language_dialect_default[argc];
(void)argv;
return require;
}

Binary file not shown.

View File

@ -0,0 +1,16 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 3.16
# Relative path conversion top directories.
set(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/duongtd/robotics_core/common_msgs/sensor_msgs")
set(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/duongtd/robotics_core/common_msgs/sensor_msgs/test")
# Force unix paths in dependencies.
set(CMAKE_FORCE_UNIX_PATHS 1)
# The C and CXX include file regular expressions for this directory.
set(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$")
set(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$")
set(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN})
set(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN})

View File

@ -0,0 +1,461 @@
The system is: Linux - 5.15.0-139-generic - x86_64
Compiling the C compiler identification source file "CMakeCCompilerId.c" succeeded.
Compiler: /usr/bin/cc
Build flags:
Id flags:
The output was:
0
Compilation of the C compiler identification source "CMakeCCompilerId.c" produced "a.out"
The C compiler identification is GNU, found in "/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/3.16.3/CompilerIdC/a.out"
Compiling the CXX compiler identification source file "CMakeCXXCompilerId.cpp" succeeded.
Compiler: /usr/bin/c++
Build flags:
Id flags:
The output was:
0
Compilation of the CXX compiler identification source "CMakeCXXCompilerId.cpp" produced "a.out"
The CXX compiler identification is GNU, found in "/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/3.16.3/CompilerIdCXX/a.out"
Determining if the C compiler works passed with the following output:
Change Dir: /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp
Run Build Command(s):/usr/bin/make cmTC_d273c/fast && /usr/bin/make -f CMakeFiles/cmTC_d273c.dir/build.make CMakeFiles/cmTC_d273c.dir/build
make[1]: Entering directory '/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp'
Building C object CMakeFiles/cmTC_d273c.dir/testCCompiler.c.o
/usr/bin/cc -o CMakeFiles/cmTC_d273c.dir/testCCompiler.c.o -c /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp/testCCompiler.c
Linking C executable cmTC_d273c
/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_d273c.dir/link.txt --verbose=1
/usr/bin/cc CMakeFiles/cmTC_d273c.dir/testCCompiler.c.o -o cmTC_d273c
make[1]: Leaving directory '/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp'
Detecting C compiler ABI info compiled with the following output:
Change Dir: /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp
Run Build Command(s):/usr/bin/make cmTC_2948f/fast && /usr/bin/make -f CMakeFiles/cmTC_2948f.dir/build.make CMakeFiles/cmTC_2948f.dir/build
make[1]: Entering directory '/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp'
Building C object CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o
/usr/bin/cc -v -o CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-3.16/Modules/CMakeCCompilerABI.c
Using built-in specs.
COLLECT_GCC=/usr/bin/cc
OFFLOAD_TARGET_NAMES=nvptx-none:hsa
OFFLOAD_TARGET_DEFAULT=1
Target: x86_64-linux-gnu
Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.2' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-9QDOt0/gcc-9-9.4.0/debian/tmp-nvptx/usr,hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu
Thread model: posix
gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.2)
COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64'
/usr/lib/gcc/x86_64-linux-gnu/9/cc1 -quiet -v -imultiarch x86_64-linux-gnu /usr/share/cmake-3.16/Modules/CMakeCCompilerABI.c -quiet -dumpbase CMakeCCompilerABI.c -mtune=generic -march=x86-64 -auxbase-strip CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/ccknjpVA.s
GNU C17 (Ubuntu 9.4.0-1ubuntu1~20.04.2) version 9.4.0 (x86_64-linux-gnu)
compiled by GNU C version 9.4.0, GMP version 6.2.0, MPFR version 4.0.2, MPC version 1.1.0, isl version isl-0.22.1-GMP
GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu"
ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/include-fixed"
ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/../../../../x86_64-linux-gnu/include"
#include "..." search starts here:
#include <...> search starts here:
/usr/lib/gcc/x86_64-linux-gnu/9/include
/usr/local/include
/usr/include/x86_64-linux-gnu
/usr/include
End of search list.
GNU C17 (Ubuntu 9.4.0-1ubuntu1~20.04.2) version 9.4.0 (x86_64-linux-gnu)
compiled by GNU C version 9.4.0, GMP version 6.2.0, MPFR version 4.0.2, MPC version 1.1.0, isl version isl-0.22.1-GMP
GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
Compiler executable checksum: 01da938ff5dc2163489aa33cb3b747a7
COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64'
as -v --64 -o CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o /tmp/ccknjpVA.s
GNU assembler version 2.34 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.34
COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/
LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/
COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64'
Linking C executable cmTC_2948f
/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_2948f.dir/link.txt --verbose=1
/usr/bin/cc -v CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o -o cmTC_2948f
Using built-in specs.
COLLECT_GCC=/usr/bin/cc
COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper
OFFLOAD_TARGET_NAMES=nvptx-none:hsa
OFFLOAD_TARGET_DEFAULT=1
Target: x86_64-linux-gnu
Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.2' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-9QDOt0/gcc-9-9.4.0/debian/tmp-nvptx/usr,hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu
Thread model: posix
gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.2)
COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/
LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/
COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_2948f' '-mtune=generic' '-march=x86-64'
/usr/lib/gcc/x86_64-linux-gnu/9/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -plugin-opt=-fresolution=/tmp/ccfspTO5.res -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_2948f /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o -L/usr/lib/gcc/x86_64-linux-gnu/9 -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/9/../../.. CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o -lgcc --push-state --as-needed -lgcc_s --pop-state -lc -lgcc --push-state --as-needed -lgcc_s --pop-state /usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o
COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_2948f' '-mtune=generic' '-march=x86-64'
make[1]: Leaving directory '/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp'
Parsed C implicit include dir info from above output: rv=done
found start of include info
found start of implicit include info
add: [/usr/lib/gcc/x86_64-linux-gnu/9/include]
add: [/usr/local/include]
add: [/usr/include/x86_64-linux-gnu]
add: [/usr/include]
end of search list found
collapse include dir [/usr/lib/gcc/x86_64-linux-gnu/9/include] ==> [/usr/lib/gcc/x86_64-linux-gnu/9/include]
collapse include dir [/usr/local/include] ==> [/usr/local/include]
collapse include dir [/usr/include/x86_64-linux-gnu] ==> [/usr/include/x86_64-linux-gnu]
collapse include dir [/usr/include] ==> [/usr/include]
implicit include dirs: [/usr/lib/gcc/x86_64-linux-gnu/9/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include]
Parsed C implicit link information from above output:
link line regex: [^( *|.*[/\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\]+-)?ld|collect2)[^/\]*( |$)]
ignore line: [Change Dir: /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp]
ignore line: []
ignore line: [Run Build Command(s):/usr/bin/make cmTC_2948f/fast && /usr/bin/make -f CMakeFiles/cmTC_2948f.dir/build.make CMakeFiles/cmTC_2948f.dir/build]
ignore line: [make[1]: Entering directory '/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp']
ignore line: [Building C object CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o]
ignore line: [/usr/bin/cc -v -o CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-3.16/Modules/CMakeCCompilerABI.c]
ignore line: [Using built-in specs.]
ignore line: [COLLECT_GCC=/usr/bin/cc]
ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:hsa]
ignore line: [OFFLOAD_TARGET_DEFAULT=1]
ignore line: [Target: x86_64-linux-gnu]
ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.2' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-9QDOt0/gcc-9-9.4.0/debian/tmp-nvptx/usr hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu]
ignore line: [Thread model: posix]
ignore line: [gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.2) ]
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64']
ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/9/cc1 -quiet -v -imultiarch x86_64-linux-gnu /usr/share/cmake-3.16/Modules/CMakeCCompilerABI.c -quiet -dumpbase CMakeCCompilerABI.c -mtune=generic -march=x86-64 -auxbase-strip CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/ccknjpVA.s]
ignore line: [GNU C17 (Ubuntu 9.4.0-1ubuntu1~20.04.2) version 9.4.0 (x86_64-linux-gnu)]
ignore line: [ compiled by GNU C version 9.4.0 GMP version 6.2.0 MPFR version 4.0.2 MPC version 1.1.0 isl version isl-0.22.1-GMP]
ignore line: []
ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
ignore line: [ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu"]
ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/include-fixed"]
ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/../../../../x86_64-linux-gnu/include"]
ignore line: [#include "..." search starts here:]
ignore line: [#include <...> search starts here:]
ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/9/include]
ignore line: [ /usr/local/include]
ignore line: [ /usr/include/x86_64-linux-gnu]
ignore line: [ /usr/include]
ignore line: [End of search list.]
ignore line: [GNU C17 (Ubuntu 9.4.0-1ubuntu1~20.04.2) version 9.4.0 (x86_64-linux-gnu)]
ignore line: [ compiled by GNU C version 9.4.0 GMP version 6.2.0 MPFR version 4.0.2 MPC version 1.1.0 isl version isl-0.22.1-GMP]
ignore line: []
ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
ignore line: [Compiler executable checksum: 01da938ff5dc2163489aa33cb3b747a7]
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64']
ignore line: [ as -v --64 -o CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o /tmp/ccknjpVA.s]
ignore line: [GNU assembler version 2.34 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.34]
ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/]
ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/]
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64']
ignore line: [Linking C executable cmTC_2948f]
ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_2948f.dir/link.txt --verbose=1]
ignore line: [/usr/bin/cc -v CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o -o cmTC_2948f ]
ignore line: [Using built-in specs.]
ignore line: [COLLECT_GCC=/usr/bin/cc]
ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper]
ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:hsa]
ignore line: [OFFLOAD_TARGET_DEFAULT=1]
ignore line: [Target: x86_64-linux-gnu]
ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.2' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-9QDOt0/gcc-9-9.4.0/debian/tmp-nvptx/usr hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu]
ignore line: [Thread model: posix]
ignore line: [gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.2) ]
ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/]
ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/]
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_2948f' '-mtune=generic' '-march=x86-64']
link line: [ /usr/lib/gcc/x86_64-linux-gnu/9/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -plugin-opt=-fresolution=/tmp/ccfspTO5.res -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_2948f /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o -L/usr/lib/gcc/x86_64-linux-gnu/9 -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/9/../../.. CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o -lgcc --push-state --as-needed -lgcc_s --pop-state -lc -lgcc --push-state --as-needed -lgcc_s --pop-state /usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o]
arg [/usr/lib/gcc/x86_64-linux-gnu/9/collect2] ==> ignore
arg [-plugin] ==> ignore
arg [/usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so] ==> ignore
arg [-plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper] ==> ignore
arg [-plugin-opt=-fresolution=/tmp/ccfspTO5.res] ==> ignore
arg [-plugin-opt=-pass-through=-lgcc] ==> ignore
arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore
arg [-plugin-opt=-pass-through=-lc] ==> ignore
arg [-plugin-opt=-pass-through=-lgcc] ==> ignore
arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore
arg [--build-id] ==> ignore
arg [--eh-frame-hdr] ==> ignore
arg [-m] ==> ignore
arg [elf_x86_64] ==> ignore
arg [--hash-style=gnu] ==> ignore
arg [--as-needed] ==> ignore
arg [-dynamic-linker] ==> ignore
arg [/lib64/ld-linux-x86-64.so.2] ==> ignore
arg [-pie] ==> ignore
arg [-znow] ==> ignore
arg [-zrelro] ==> ignore
arg [-o] ==> ignore
arg [cmTC_2948f] ==> ignore
arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o] ==> ignore
arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o] ==> ignore
arg [/usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o] ==> ignore
arg [-L/usr/lib/gcc/x86_64-linux-gnu/9] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9]
arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu]
arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib]
arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu]
arg [-L/lib/../lib] ==> dir [/lib/../lib]
arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu]
arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib]
arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../..]
arg [CMakeFiles/cmTC_2948f.dir/CMakeCCompilerABI.c.o] ==> ignore
arg [-lgcc] ==> lib [gcc]
arg [--push-state] ==> ignore
arg [--as-needed] ==> ignore
arg [-lgcc_s] ==> lib [gcc_s]
arg [--pop-state] ==> ignore
arg [-lc] ==> lib [c]
arg [-lgcc] ==> lib [gcc]
arg [--push-state] ==> ignore
arg [--as-needed] ==> ignore
arg [-lgcc_s] ==> lib [gcc_s]
arg [--pop-state] ==> ignore
arg [/usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o] ==> ignore
arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o] ==> ignore
collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9] ==> [/usr/lib/gcc/x86_64-linux-gnu/9]
collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu]
collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] ==> [/usr/lib]
collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu]
collapse library dir [/lib/../lib] ==> [/lib]
collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu]
collapse library dir [/usr/lib/../lib] ==> [/usr/lib]
collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../..] ==> [/usr/lib]
implicit libs: [gcc;gcc_s;c;gcc;gcc_s]
implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/9;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib]
implicit fwks: []
Determining if the CXX compiler works passed with the following output:
Change Dir: /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp
Run Build Command(s):/usr/bin/make cmTC_7b06d/fast && /usr/bin/make -f CMakeFiles/cmTC_7b06d.dir/build.make CMakeFiles/cmTC_7b06d.dir/build
make[1]: Entering directory '/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp'
Building CXX object CMakeFiles/cmTC_7b06d.dir/testCXXCompiler.cxx.o
/usr/bin/c++ -o CMakeFiles/cmTC_7b06d.dir/testCXXCompiler.cxx.o -c /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp/testCXXCompiler.cxx
Linking CXX executable cmTC_7b06d
/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_7b06d.dir/link.txt --verbose=1
/usr/bin/c++ CMakeFiles/cmTC_7b06d.dir/testCXXCompiler.cxx.o -o cmTC_7b06d
make[1]: Leaving directory '/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp'
Detecting CXX compiler ABI info compiled with the following output:
Change Dir: /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp
Run Build Command(s):/usr/bin/make cmTC_479df/fast && /usr/bin/make -f CMakeFiles/cmTC_479df.dir/build.make CMakeFiles/cmTC_479df.dir/build
make[1]: Entering directory '/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp'
Building CXX object CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o
/usr/bin/c++ -v -o CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-3.16/Modules/CMakeCXXCompilerABI.cpp
Using built-in specs.
COLLECT_GCC=/usr/bin/c++
OFFLOAD_TARGET_NAMES=nvptx-none:hsa
OFFLOAD_TARGET_DEFAULT=1
Target: x86_64-linux-gnu
Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.2' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-9QDOt0/gcc-9-9.4.0/debian/tmp-nvptx/usr,hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu
Thread model: posix
gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.2)
COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64'
/usr/lib/gcc/x86_64-linux-gnu/9/cc1plus -quiet -v -imultiarch x86_64-linux-gnu -D_GNU_SOURCE /usr/share/cmake-3.16/Modules/CMakeCXXCompilerABI.cpp -quiet -dumpbase CMakeCXXCompilerABI.cpp -mtune=generic -march=x86-64 -auxbase-strip CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/ccqwJhLz.s
GNU C++14 (Ubuntu 9.4.0-1ubuntu1~20.04.2) version 9.4.0 (x86_64-linux-gnu)
compiled by GNU C version 9.4.0, GMP version 6.2.0, MPFR version 4.0.2, MPC version 1.1.0, isl version isl-0.22.1-GMP
GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
ignoring duplicate directory "/usr/include/x86_64-linux-gnu/c++/9"
ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu"
ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/include-fixed"
ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/../../../../x86_64-linux-gnu/include"
#include "..." search starts here:
#include <...> search starts here:
/usr/include/c++/9
/usr/include/x86_64-linux-gnu/c++/9
/usr/include/c++/9/backward
/usr/lib/gcc/x86_64-linux-gnu/9/include
/usr/local/include
/usr/include/x86_64-linux-gnu
/usr/include
End of search list.
GNU C++14 (Ubuntu 9.4.0-1ubuntu1~20.04.2) version 9.4.0 (x86_64-linux-gnu)
compiled by GNU C version 9.4.0, GMP version 6.2.0, MPFR version 4.0.2, MPC version 1.1.0, isl version isl-0.22.1-GMP
GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
Compiler executable checksum: 3d1eba838554fa2348dba760e4770469
COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64'
as -v --64 -o CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o /tmp/ccqwJhLz.s
GNU assembler version 2.34 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.34
COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/
LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/
COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64'
Linking CXX executable cmTC_479df
/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_479df.dir/link.txt --verbose=1
/usr/bin/c++ -v CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o -o cmTC_479df
Using built-in specs.
COLLECT_GCC=/usr/bin/c++
COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper
OFFLOAD_TARGET_NAMES=nvptx-none:hsa
OFFLOAD_TARGET_DEFAULT=1
Target: x86_64-linux-gnu
Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.2' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-9QDOt0/gcc-9-9.4.0/debian/tmp-nvptx/usr,hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu
Thread model: posix
gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.2)
COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/
LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/
COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_479df' '-shared-libgcc' '-mtune=generic' '-march=x86-64'
/usr/lib/gcc/x86_64-linux-gnu/9/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -plugin-opt=-fresolution=/tmp/ccFTkvC3.res -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_479df /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o -L/usr/lib/gcc/x86_64-linux-gnu/9 -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/9/../../.. CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o
COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_479df' '-shared-libgcc' '-mtune=generic' '-march=x86-64'
make[1]: Leaving directory '/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp'
Parsed CXX implicit include dir info from above output: rv=done
found start of include info
found start of implicit include info
add: [/usr/include/c++/9]
add: [/usr/include/x86_64-linux-gnu/c++/9]
add: [/usr/include/c++/9/backward]
add: [/usr/lib/gcc/x86_64-linux-gnu/9/include]
add: [/usr/local/include]
add: [/usr/include/x86_64-linux-gnu]
add: [/usr/include]
end of search list found
collapse include dir [/usr/include/c++/9] ==> [/usr/include/c++/9]
collapse include dir [/usr/include/x86_64-linux-gnu/c++/9] ==> [/usr/include/x86_64-linux-gnu/c++/9]
collapse include dir [/usr/include/c++/9/backward] ==> [/usr/include/c++/9/backward]
collapse include dir [/usr/lib/gcc/x86_64-linux-gnu/9/include] ==> [/usr/lib/gcc/x86_64-linux-gnu/9/include]
collapse include dir [/usr/local/include] ==> [/usr/local/include]
collapse include dir [/usr/include/x86_64-linux-gnu] ==> [/usr/include/x86_64-linux-gnu]
collapse include dir [/usr/include] ==> [/usr/include]
implicit include dirs: [/usr/include/c++/9;/usr/include/x86_64-linux-gnu/c++/9;/usr/include/c++/9/backward;/usr/lib/gcc/x86_64-linux-gnu/9/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include]
Parsed CXX implicit link information from above output:
link line regex: [^( *|.*[/\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\]+-)?ld|collect2)[^/\]*( |$)]
ignore line: [Change Dir: /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp]
ignore line: []
ignore line: [Run Build Command(s):/usr/bin/make cmTC_479df/fast && /usr/bin/make -f CMakeFiles/cmTC_479df.dir/build.make CMakeFiles/cmTC_479df.dir/build]
ignore line: [make[1]: Entering directory '/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/CMakeTmp']
ignore line: [Building CXX object CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o]
ignore line: [/usr/bin/c++ -v -o CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-3.16/Modules/CMakeCXXCompilerABI.cpp]
ignore line: [Using built-in specs.]
ignore line: [COLLECT_GCC=/usr/bin/c++]
ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:hsa]
ignore line: [OFFLOAD_TARGET_DEFAULT=1]
ignore line: [Target: x86_64-linux-gnu]
ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.2' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-9QDOt0/gcc-9-9.4.0/debian/tmp-nvptx/usr hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu]
ignore line: [Thread model: posix]
ignore line: [gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.2) ]
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64']
ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/9/cc1plus -quiet -v -imultiarch x86_64-linux-gnu -D_GNU_SOURCE /usr/share/cmake-3.16/Modules/CMakeCXXCompilerABI.cpp -quiet -dumpbase CMakeCXXCompilerABI.cpp -mtune=generic -march=x86-64 -auxbase-strip CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/ccqwJhLz.s]
ignore line: [GNU C++14 (Ubuntu 9.4.0-1ubuntu1~20.04.2) version 9.4.0 (x86_64-linux-gnu)]
ignore line: [ compiled by GNU C version 9.4.0 GMP version 6.2.0 MPFR version 4.0.2 MPC version 1.1.0 isl version isl-0.22.1-GMP]
ignore line: []
ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
ignore line: [ignoring duplicate directory "/usr/include/x86_64-linux-gnu/c++/9"]
ignore line: [ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu"]
ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/include-fixed"]
ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/9/../../../../x86_64-linux-gnu/include"]
ignore line: [#include "..." search starts here:]
ignore line: [#include <...> search starts here:]
ignore line: [ /usr/include/c++/9]
ignore line: [ /usr/include/x86_64-linux-gnu/c++/9]
ignore line: [ /usr/include/c++/9/backward]
ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/9/include]
ignore line: [ /usr/local/include]
ignore line: [ /usr/include/x86_64-linux-gnu]
ignore line: [ /usr/include]
ignore line: [End of search list.]
ignore line: [GNU C++14 (Ubuntu 9.4.0-1ubuntu1~20.04.2) version 9.4.0 (x86_64-linux-gnu)]
ignore line: [ compiled by GNU C version 9.4.0 GMP version 6.2.0 MPFR version 4.0.2 MPC version 1.1.0 isl version isl-0.22.1-GMP]
ignore line: []
ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
ignore line: [Compiler executable checksum: 3d1eba838554fa2348dba760e4770469]
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64']
ignore line: [ as -v --64 -o CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o /tmp/ccqwJhLz.s]
ignore line: [GNU assembler version 2.34 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.34]
ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/]
ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/]
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64']
ignore line: [Linking CXX executable cmTC_479df]
ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_479df.dir/link.txt --verbose=1]
ignore line: [/usr/bin/c++ -v CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o -o cmTC_479df ]
ignore line: [Using built-in specs.]
ignore line: [COLLECT_GCC=/usr/bin/c++]
ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper]
ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:hsa]
ignore line: [OFFLOAD_TARGET_DEFAULT=1]
ignore line: [Target: x86_64-linux-gnu]
ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 9.4.0-1ubuntu1~20.04.2' --with-bugurl=file:///usr/share/doc/gcc-9/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ gm2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-9 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-9-9QDOt0/gcc-9-9.4.0/debian/tmp-nvptx/usr hsa --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu]
ignore line: [Thread model: posix]
ignore line: [gcc version 9.4.0 (Ubuntu 9.4.0-1ubuntu1~20.04.2) ]
ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/]
ignore line: [LIBRARY_PATH=/usr/lib/gcc/x86_64-linux-gnu/9/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/9/../../../:/lib/:/usr/lib/]
ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_479df' '-shared-libgcc' '-mtune=generic' '-march=x86-64']
link line: [ /usr/lib/gcc/x86_64-linux-gnu/9/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper -plugin-opt=-fresolution=/tmp/ccFTkvC3.res -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_479df /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o -L/usr/lib/gcc/x86_64-linux-gnu/9 -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/9/../../.. CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o]
arg [/usr/lib/gcc/x86_64-linux-gnu/9/collect2] ==> ignore
arg [-plugin] ==> ignore
arg [/usr/lib/gcc/x86_64-linux-gnu/9/liblto_plugin.so] ==> ignore
arg [-plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/9/lto-wrapper] ==> ignore
arg [-plugin-opt=-fresolution=/tmp/ccFTkvC3.res] ==> ignore
arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore
arg [-plugin-opt=-pass-through=-lgcc] ==> ignore
arg [-plugin-opt=-pass-through=-lc] ==> ignore
arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore
arg [-plugin-opt=-pass-through=-lgcc] ==> ignore
arg [--build-id] ==> ignore
arg [--eh-frame-hdr] ==> ignore
arg [-m] ==> ignore
arg [elf_x86_64] ==> ignore
arg [--hash-style=gnu] ==> ignore
arg [--as-needed] ==> ignore
arg [-dynamic-linker] ==> ignore
arg [/lib64/ld-linux-x86-64.so.2] ==> ignore
arg [-pie] ==> ignore
arg [-znow] ==> ignore
arg [-zrelro] ==> ignore
arg [-o] ==> ignore
arg [cmTC_479df] ==> ignore
arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/Scrt1.o] ==> ignore
arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crti.o] ==> ignore
arg [/usr/lib/gcc/x86_64-linux-gnu/9/crtbeginS.o] ==> ignore
arg [-L/usr/lib/gcc/x86_64-linux-gnu/9] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9]
arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu]
arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib]
arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu]
arg [-L/lib/../lib] ==> dir [/lib/../lib]
arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu]
arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib]
arg [-L/usr/lib/gcc/x86_64-linux-gnu/9/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../..]
arg [CMakeFiles/cmTC_479df.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore
arg [-lstdc++] ==> lib [stdc++]
arg [-lm] ==> lib [m]
arg [-lgcc_s] ==> lib [gcc_s]
arg [-lgcc] ==> lib [gcc]
arg [-lc] ==> lib [c]
arg [-lgcc_s] ==> lib [gcc_s]
arg [-lgcc] ==> lib [gcc]
arg [/usr/lib/gcc/x86_64-linux-gnu/9/crtendS.o] ==> ignore
arg [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu/crtn.o] ==> ignore
collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9] ==> [/usr/lib/gcc/x86_64-linux-gnu/9]
collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu]
collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../../../lib] ==> [/usr/lib]
collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu]
collapse library dir [/lib/../lib] ==> [/lib]
collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu]
collapse library dir [/usr/lib/../lib] ==> [/usr/lib]
collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/9/../../..] ==> [/usr/lib]
implicit libs: [stdc++;m;gcc_s;gcc;c;gcc_s;gcc]
implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/9;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib]
implicit fwks: []

View File

@ -0,0 +1,51 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 3.16
# The generator used is:
set(CMAKE_DEPENDS_GENERATOR "Unix Makefiles")
# The top level Makefile was generated from the following files:
set(CMAKE_MAKEFILE_DEPENDS
"CMakeCache.txt"
"../CMakeLists.txt"
"CMakeFiles/3.16.3/CMakeCCompiler.cmake"
"CMakeFiles/3.16.3/CMakeCXXCompiler.cmake"
"CMakeFiles/3.16.3/CMakeSystem.cmake"
"/home/duongtd/robotics_core/common_msgs/std_msgs/CMakeLists.txt"
"/usr/share/cmake-3.16/Modules/CMakeCInformation.cmake"
"/usr/share/cmake-3.16/Modules/CMakeCXXInformation.cmake"
"/usr/share/cmake-3.16/Modules/CMakeCheckCompilerFlagCommonPatterns.cmake"
"/usr/share/cmake-3.16/Modules/CMakeCommonLanguageInclude.cmake"
"/usr/share/cmake-3.16/Modules/CMakeGenericSystem.cmake"
"/usr/share/cmake-3.16/Modules/CMakeInitializeConfigs.cmake"
"/usr/share/cmake-3.16/Modules/CMakeLanguageInformation.cmake"
"/usr/share/cmake-3.16/Modules/CMakeSystemSpecificInformation.cmake"
"/usr/share/cmake-3.16/Modules/CMakeSystemSpecificInitialize.cmake"
"/usr/share/cmake-3.16/Modules/Compiler/CMakeCommonCompilerMacros.cmake"
"/usr/share/cmake-3.16/Modules/Compiler/GNU-C.cmake"
"/usr/share/cmake-3.16/Modules/Compiler/GNU-CXX.cmake"
"/usr/share/cmake-3.16/Modules/Compiler/GNU.cmake"
"/usr/share/cmake-3.16/Modules/Internal/CMakeCheckCompilerFlag.cmake"
"/usr/share/cmake-3.16/Modules/Platform/Linux-GNU-C.cmake"
"/usr/share/cmake-3.16/Modules/Platform/Linux-GNU-CXX.cmake"
"/usr/share/cmake-3.16/Modules/Platform/Linux-GNU.cmake"
"/usr/share/cmake-3.16/Modules/Platform/Linux.cmake"
"/usr/share/cmake-3.16/Modules/Platform/UnixPaths.cmake"
)
# The corresponding makefile is:
set(CMAKE_MAKEFILE_OUTPUTS
"Makefile"
"CMakeFiles/cmake.check_cache"
)
# Byproducts of CMake generate step:
set(CMAKE_MAKEFILE_PRODUCTS
"CMakeFiles/CMakeDirectoryInformation.cmake"
"std_msgs_build/CMakeFiles/CMakeDirectoryInformation.cmake"
)
# Dependency information for all targets:
set(CMAKE_DEPEND_INFO_FILES
"CMakeFiles/test_battery_state.dir/DependInfo.cmake"
)

View File

@ -0,0 +1,126 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 3.16
# Default target executed when no arguments are given to make.
default_target: all
.PHONY : default_target
#=============================================================================
# Special targets provided by cmake.
# Disable implicit rules so canonical targets will work.
.SUFFIXES:
# Remove some rules from gmake that .SUFFIXES does not remove.
SUFFIXES =
.SUFFIXES: .hpux_make_needs_suffix_list
# Suppress display of executed commands.
$(VERBOSE).SILENT:
# A target that is always out of date.
cmake_force:
.PHONY : cmake_force
#=============================================================================
# Set environment variables for the build.
# The shell in which to execute make rules.
SHELL = /bin/sh
# The CMake executable.
CMAKE_COMMAND = /usr/bin/cmake
# The command to remove a file.
RM = /usr/bin/cmake -E remove -f
# Escaping for special characters.
EQUALS = =
# The top-level source directory on which CMake was run.
CMAKE_SOURCE_DIR = /home/duongtd/robotics_core/common_msgs/sensor_msgs
# The top-level build directory on which CMake was run.
CMAKE_BINARY_DIR = /home/duongtd/robotics_core/common_msgs/sensor_msgs/test
#=============================================================================
# Directory level rules for the build root directory
# The main recursive "all" target.
all: CMakeFiles/test_battery_state.dir/all
all: std_msgs_build/all
.PHONY : all
# The main recursive "preinstall" target.
preinstall: std_msgs_build/preinstall
.PHONY : preinstall
# The main recursive "clean" target.
clean: CMakeFiles/test_battery_state.dir/clean
clean: std_msgs_build/clean
.PHONY : clean
#=============================================================================
# Directory level rules for directory std_msgs_build
# Recursive "all" directory target.
std_msgs_build/all:
.PHONY : std_msgs_build/all
# Recursive "preinstall" directory target.
std_msgs_build/preinstall:
.PHONY : std_msgs_build/preinstall
# Recursive "clean" directory target.
std_msgs_build/clean:
.PHONY : std_msgs_build/clean
#=============================================================================
# Target rules for target CMakeFiles/test_battery_state.dir
# All Build rule for target.
CMakeFiles/test_battery_state.dir/all:
$(MAKE) -f CMakeFiles/test_battery_state.dir/build.make CMakeFiles/test_battery_state.dir/depend
$(MAKE) -f CMakeFiles/test_battery_state.dir/build.make CMakeFiles/test_battery_state.dir/build
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles --progress-num=1,2 "Built target test_battery_state"
.PHONY : CMakeFiles/test_battery_state.dir/all
# Build rule for subdir invocation for target.
CMakeFiles/test_battery_state.dir/rule: cmake_check_build_system
$(CMAKE_COMMAND) -E cmake_progress_start /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles 2
$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/test_battery_state.dir/all
$(CMAKE_COMMAND) -E cmake_progress_start /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles 0
.PHONY : CMakeFiles/test_battery_state.dir/rule
# Convenience name for target.
test_battery_state: CMakeFiles/test_battery_state.dir/rule
.PHONY : test_battery_state
# clean rule for target.
CMakeFiles/test_battery_state.dir/clean:
$(MAKE) -f CMakeFiles/test_battery_state.dir/build.make CMakeFiles/test_battery_state.dir/clean
.PHONY : CMakeFiles/test_battery_state.dir/clean
#=============================================================================
# Special targets to cleanup operation of make.
# Special rule to run CMake to check the build system integrity.
# No rule that depends on this can have commands that come from listfiles
# because they might be regenerated.
cmake_check_build_system:
$(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0
.PHONY : cmake_check_build_system

View File

@ -0,0 +1,5 @@
/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/rebuild_cache.dir
/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/edit_cache.dir
/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/test_battery_state.dir
/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/std_msgs_build/CMakeFiles/rebuild_cache.dir
/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/std_msgs_build/CMakeFiles/edit_cache.dir

View File

@ -0,0 +1 @@
# This file is generated by cmake for dependency checking of the CMakeCache.txt file

View File

@ -0,0 +1 @@
2

View File

@ -0,0 +1,68 @@
#IncludeRegexLine: ^[ ]*[#%][ ]*(include|import)[ ]*[<"]([^">]+)([">])
#IncludeRegexScan: ^.*$
#IncludeRegexComplain: ^$
#IncludeRegexTransform:
../include/sensor_msgs/BatteryState.h
std_msgs/Header.h
../include/sensor_msgs/std_msgs/Header.h
cstdint
-
string
-
vector
-
limits
-
../include/sensor_msgs/JoyFeedback.h
cstdint
-
../include/sensor_msgs/JoyFeedbackArray.h
vector
-
sensor_msgs/JoyFeedback.h
../include/sensor_msgs/sensor_msgs/JoyFeedback.h
../include/sensor_msgs/PointCloud2.h
cstdint
-
string
-
vector
-
std_msgs/Header.h
../include/sensor_msgs/std_msgs/Header.h
sensor_msgs/PointField.h
../include/sensor_msgs/sensor_msgs/PointField.h
../include/sensor_msgs/PointField.h
cstdint
-
string
-
/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/main.cpp
sensor_msgs/BatteryState.h
/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/sensor_msgs/BatteryState.h
sensor_msgs/JoyFeedbackArray.h
/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/sensor_msgs/JoyFeedbackArray.h
sensor_msgs/PointCloud2.h
/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/sensor_msgs/PointCloud2.h
iostream
-
yaml-cpp/yaml.h
-
/home/duongtd/robotics_core/common_msgs/std_msgs/include/std_msgs/Header.h
string
-
chrono
-
cstdint
-

View File

@ -0,0 +1,22 @@
# The set of languages for which implicit dependencies are needed:
set(CMAKE_DEPENDS_LANGUAGES
"CXX"
)
# The set of files for implicit dependencies of each language:
set(CMAKE_DEPENDS_CHECK_CXX
"/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/main.cpp" "/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/test_battery_state.dir/main.cpp.o"
)
set(CMAKE_CXX_COMPILER_ID "GNU")
# The include file search paths:
set(CMAKE_CXX_TARGET_INCLUDE_PATH
"../include"
"/home/duongtd/robotics_core/common_msgs/std_msgs/include"
)
# Targets to which this target links.
set(CMAKE_TARGET_LINKED_INFO_FILES
)
# Fortran module output directory.
set(CMAKE_Fortran_TARGET_MODULE_DIR "")

View File

@ -0,0 +1,98 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 3.16
# Delete rule output on recipe failure.
.DELETE_ON_ERROR:
#=============================================================================
# Special targets provided by cmake.
# Disable implicit rules so canonical targets will work.
.SUFFIXES:
# Remove some rules from gmake that .SUFFIXES does not remove.
SUFFIXES =
.SUFFIXES: .hpux_make_needs_suffix_list
# Suppress display of executed commands.
$(VERBOSE).SILENT:
# A target that is always out of date.
cmake_force:
.PHONY : cmake_force
#=============================================================================
# Set environment variables for the build.
# The shell in which to execute make rules.
SHELL = /bin/sh
# The CMake executable.
CMAKE_COMMAND = /usr/bin/cmake
# The command to remove a file.
RM = /usr/bin/cmake -E remove -f
# Escaping for special characters.
EQUALS = =
# The top-level source directory on which CMake was run.
CMAKE_SOURCE_DIR = /home/duongtd/robotics_core/common_msgs/sensor_msgs
# The top-level build directory on which CMake was run.
CMAKE_BINARY_DIR = /home/duongtd/robotics_core/common_msgs/sensor_msgs/test
# Include any dependencies generated for this target.
include CMakeFiles/test_battery_state.dir/depend.make
# Include the progress variables for this target.
include CMakeFiles/test_battery_state.dir/progress.make
# Include the compile flags for this target's objects.
include CMakeFiles/test_battery_state.dir/flags.make
CMakeFiles/test_battery_state.dir/main.cpp.o: CMakeFiles/test_battery_state.dir/flags.make
CMakeFiles/test_battery_state.dir/main.cpp.o: main.cpp
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles --progress-num=$(CMAKE_PROGRESS_1) "Building CXX object CMakeFiles/test_battery_state.dir/main.cpp.o"
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -o CMakeFiles/test_battery_state.dir/main.cpp.o -c /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/main.cpp
CMakeFiles/test_battery_state.dir/main.cpp.i: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/test_battery_state.dir/main.cpp.i"
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/main.cpp > CMakeFiles/test_battery_state.dir/main.cpp.i
CMakeFiles/test_battery_state.dir/main.cpp.s: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/test_battery_state.dir/main.cpp.s"
/usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/main.cpp -o CMakeFiles/test_battery_state.dir/main.cpp.s
# Object files for target test_battery_state
test_battery_state_OBJECTS = \
"CMakeFiles/test_battery_state.dir/main.cpp.o"
# External object files for target test_battery_state
test_battery_state_EXTERNAL_OBJECTS =
test_battery_state: CMakeFiles/test_battery_state.dir/main.cpp.o
test_battery_state: CMakeFiles/test_battery_state.dir/build.make
test_battery_state: CMakeFiles/test_battery_state.dir/link.txt
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --bold --progress-dir=/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles --progress-num=$(CMAKE_PROGRESS_2) "Linking CXX executable test_battery_state"
$(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/test_battery_state.dir/link.txt --verbose=$(VERBOSE)
# Rule to build all files generated by this target.
CMakeFiles/test_battery_state.dir/build: test_battery_state
.PHONY : CMakeFiles/test_battery_state.dir/build
CMakeFiles/test_battery_state.dir/clean:
$(CMAKE_COMMAND) -P CMakeFiles/test_battery_state.dir/cmake_clean.cmake
.PHONY : CMakeFiles/test_battery_state.dir/clean
CMakeFiles/test_battery_state.dir/depend:
cd /home/duongtd/robotics_core/common_msgs/sensor_msgs/test && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/duongtd/robotics_core/common_msgs/sensor_msgs /home/duongtd/robotics_core/common_msgs/sensor_msgs /home/duongtd/robotics_core/common_msgs/sensor_msgs/test /home/duongtd/robotics_core/common_msgs/sensor_msgs/test /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/test_battery_state.dir/DependInfo.cmake --color=$(COLOR)
.PHONY : CMakeFiles/test_battery_state.dir/depend

View File

@ -0,0 +1,10 @@
file(REMOVE_RECURSE
"CMakeFiles/test_battery_state.dir/main.cpp.o"
"test_battery_state"
"test_battery_state.pdb"
)
# Per-language clean rules from dependency scanning.
foreach(lang CXX)
include(CMakeFiles/test_battery_state.dir/cmake_clean_${lang}.cmake OPTIONAL)
endforeach()

View File

@ -0,0 +1,11 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 3.16
CMakeFiles/test_battery_state.dir/main.cpp.o
../include/sensor_msgs/BatteryState.h
../include/sensor_msgs/JoyFeedback.h
../include/sensor_msgs/JoyFeedbackArray.h
../include/sensor_msgs/PointCloud2.h
../include/sensor_msgs/PointField.h
/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/main.cpp
/home/duongtd/robotics_core/common_msgs/std_msgs/include/std_msgs/Header.h

View File

@ -0,0 +1,11 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 3.16
CMakeFiles/test_battery_state.dir/main.cpp.o: ../include/sensor_msgs/BatteryState.h
CMakeFiles/test_battery_state.dir/main.cpp.o: ../include/sensor_msgs/JoyFeedback.h
CMakeFiles/test_battery_state.dir/main.cpp.o: ../include/sensor_msgs/JoyFeedbackArray.h
CMakeFiles/test_battery_state.dir/main.cpp.o: ../include/sensor_msgs/PointCloud2.h
CMakeFiles/test_battery_state.dir/main.cpp.o: ../include/sensor_msgs/PointField.h
CMakeFiles/test_battery_state.dir/main.cpp.o: main.cpp
CMakeFiles/test_battery_state.dir/main.cpp.o: /home/duongtd/robotics_core/common_msgs/std_msgs/include/std_msgs/Header.h

View File

@ -0,0 +1,10 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 3.16
# compile CXX with /usr/bin/c++
CXX_FLAGS = -std=gnu++17
CXX_DEFINES =
CXX_INCLUDES = -I/home/duongtd/robotics_core/common_msgs/sensor_msgs/include -I/home/duongtd/robotics_core/common_msgs/std_msgs/include

View File

@ -0,0 +1 @@
/usr/bin/c++ CMakeFiles/test_battery_state.dir/main.cpp.o -o test_battery_state -lyaml-cpp

View File

@ -0,0 +1,3 @@
CMAKE_PROGRESS_1 = 1
CMAKE_PROGRESS_2 = 2

178
sensor_msgs/test/Makefile Normal file
View File

@ -0,0 +1,178 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 3.16
# Default target executed when no arguments are given to make.
default_target: all
.PHONY : default_target
# Allow only one "make -f Makefile2" at a time, but pass parallelism.
.NOTPARALLEL:
#=============================================================================
# Special targets provided by cmake.
# Disable implicit rules so canonical targets will work.
.SUFFIXES:
# Remove some rules from gmake that .SUFFIXES does not remove.
SUFFIXES =
.SUFFIXES: .hpux_make_needs_suffix_list
# Suppress display of executed commands.
$(VERBOSE).SILENT:
# A target that is always out of date.
cmake_force:
.PHONY : cmake_force
#=============================================================================
# Set environment variables for the build.
# The shell in which to execute make rules.
SHELL = /bin/sh
# The CMake executable.
CMAKE_COMMAND = /usr/bin/cmake
# The command to remove a file.
RM = /usr/bin/cmake -E remove -f
# Escaping for special characters.
EQUALS = =
# The top-level source directory on which CMake was run.
CMAKE_SOURCE_DIR = /home/duongtd/robotics_core/common_msgs/sensor_msgs
# The top-level build directory on which CMake was run.
CMAKE_BINARY_DIR = /home/duongtd/robotics_core/common_msgs/sensor_msgs/test
#=============================================================================
# Targets provided globally by CMake.
# Special rule for the target rebuild_cache
rebuild_cache:
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..."
/usr/bin/cmake -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
.PHONY : rebuild_cache
# Special rule for the target rebuild_cache
rebuild_cache/fast: rebuild_cache
.PHONY : rebuild_cache/fast
# Special rule for the target edit_cache
edit_cache:
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "No interactive CMake dialog available..."
/usr/bin/cmake -E echo No\ interactive\ CMake\ dialog\ available.
.PHONY : edit_cache
# Special rule for the target edit_cache
edit_cache/fast: edit_cache
.PHONY : edit_cache/fast
# The main all target
all: cmake_check_build_system
$(CMAKE_COMMAND) -E cmake_progress_start /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles/progress.marks
$(MAKE) -f CMakeFiles/Makefile2 all
$(CMAKE_COMMAND) -E cmake_progress_start /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles 0
.PHONY : all
# The main clean target
clean:
$(MAKE) -f CMakeFiles/Makefile2 clean
.PHONY : clean
# The main clean target
clean/fast: clean
.PHONY : clean/fast
# Prepare targets for installation.
preinstall: all
$(MAKE) -f CMakeFiles/Makefile2 preinstall
.PHONY : preinstall
# Prepare targets for installation.
preinstall/fast:
$(MAKE) -f CMakeFiles/Makefile2 preinstall
.PHONY : preinstall/fast
# clear depends
depend:
$(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1
.PHONY : depend
#=============================================================================
# Target rules for targets named test_battery_state
# Build rule for target.
test_battery_state: cmake_check_build_system
$(MAKE) -f CMakeFiles/Makefile2 test_battery_state
.PHONY : test_battery_state
# fast build rule for target.
test_battery_state/fast:
$(MAKE) -f CMakeFiles/test_battery_state.dir/build.make CMakeFiles/test_battery_state.dir/build
.PHONY : test_battery_state/fast
main.o: main.cpp.o
.PHONY : main.o
# target to build an object file
main.cpp.o:
$(MAKE) -f CMakeFiles/test_battery_state.dir/build.make CMakeFiles/test_battery_state.dir/main.cpp.o
.PHONY : main.cpp.o
main.i: main.cpp.i
.PHONY : main.i
# target to preprocess a source file
main.cpp.i:
$(MAKE) -f CMakeFiles/test_battery_state.dir/build.make CMakeFiles/test_battery_state.dir/main.cpp.i
.PHONY : main.cpp.i
main.s: main.cpp.s
.PHONY : main.s
# target to generate assembly for a file
main.cpp.s:
$(MAKE) -f CMakeFiles/test_battery_state.dir/build.make CMakeFiles/test_battery_state.dir/main.cpp.s
.PHONY : main.cpp.s
# Help Target
help:
@echo "The following are some of the valid targets for this Makefile:"
@echo "... all (the default if no target is provided)"
@echo "... clean"
@echo "... depend"
@echo "... rebuild_cache"
@echo "... edit_cache"
@echo "... test_battery_state"
@echo "... main.o"
@echo "... main.i"
@echo "... main.s"
.PHONY : help
#=============================================================================
# Special targets to cleanup operation of make.
# Special rule to run CMake to check the build system integrity.
# No rule that depends on this can have commands that come from listfiles
# because they might be regenerated.
cmake_check_build_system:
$(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0
.PHONY : cmake_check_build_system

View File

@ -0,0 +1,55 @@
# Install script for directory: /home/duongtd/robotics_core/common_msgs/sensor_msgs
# Set the install prefix
if(NOT DEFINED CMAKE_INSTALL_PREFIX)
set(CMAKE_INSTALL_PREFIX "/usr/local")
endif()
string(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
# Set the install configuration name.
if(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME)
if(BUILD_TYPE)
string(REGEX REPLACE "^[^A-Za-z0-9_]+" ""
CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}")
else()
set(CMAKE_INSTALL_CONFIG_NAME "")
endif()
message(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"")
endif()
# Set the component getting installed.
if(NOT CMAKE_INSTALL_COMPONENT)
if(COMPONENT)
message(STATUS "Install component: \"${COMPONENT}\"")
set(CMAKE_INSTALL_COMPONENT "${COMPONENT}")
else()
set(CMAKE_INSTALL_COMPONENT)
endif()
endif()
# Install shared libraries without execute permission?
if(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE)
set(CMAKE_INSTALL_SO_NO_EXE "1")
endif()
# Is this installation the result of a crosscompile?
if(NOT DEFINED CMAKE_CROSSCOMPILING)
set(CMAKE_CROSSCOMPILING "FALSE")
endif()
if(NOT CMAKE_INSTALL_LOCAL_ONLY)
# Include the install script for each subdirectory.
include("/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/std_msgs_build/cmake_install.cmake")
endif()
if(CMAKE_INSTALL_COMPONENT)
set(CMAKE_INSTALL_MANIFEST "install_manifest_${CMAKE_INSTALL_COMPONENT}.txt")
else()
set(CMAKE_INSTALL_MANIFEST "install_manifest.txt")
endif()
string(REPLACE ";" "\n" CMAKE_INSTALL_MANIFEST_CONTENT
"${CMAKE_INSTALL_MANIFEST_FILES}")
file(WRITE "/home/duongtd/robotics_core/common_msgs/sensor_msgs/test/${CMAKE_INSTALL_MANIFEST}"
"${CMAKE_INSTALL_MANIFEST_CONTENT}")

75
sensor_msgs/test/main.cpp Normal file
View File

@ -0,0 +1,75 @@
#include "sensor_msgs/BatteryState.h"
#include "sensor_msgs/JoyFeedbackArray.h"
#include "sensor_msgs/PointCloud2.h"
#include <iostream>
#include <yaml-cpp/yaml.h>
bool getParams()
{
try {
YAML::Node config = YAML::LoadFile("../cfg/config.yaml");
double cost_scaling_factor = config["inflation_layer"]["cost_scaling_factor"].as<double>();
double inflation_radius = config["inflation_layer"]["inflation_radius"].as<double>();
bool enabled = config["inflation_layer"]["enabled"].as<bool>();
bool inflate_unknown = config["inflation_layer"]["inflate_unknown"].as<bool>();
double distance = config["obstacle_layer"]["distance"].as<double>();
std::cout << "Inflation Layer Parameters:" << std::endl;
std::cout << " Cost Scaling Factor: " << cost_scaling_factor << std::endl;
std::cout << " Inflation Radius: " << inflation_radius << std::endl;
std::cout << " Enabled: " << (enabled ? "true" : "false") << std::endl;
std::cout << " Inflate Unknown: " << (inflate_unknown ? "true" : "false") << std::endl;
std::cout << "Obstacle Layer Parameters:" << std::endl;
std::cout << " Distance: " << distance << std::endl;
}
catch (const YAML::BadFile& e) {
std::cerr << "Cannot open YAML file: " << e.what() << std::endl;
return false;
}
return true;
}
int main()
{
getParams();
sensor_msgs::BatteryState battery;
battery.header = std_msgs::Header::now("battery_frame");
battery.voltage = 12.5f;
battery.current = -1.2f;
battery.percentage = 0.85f;
battery.power_supply_status = sensor_msgs::BatteryState::POWER_SUPPLY_STATUS_DISCHARGING;
battery.cell_voltage = {4.15f, 4.18f, 4.12f};
battery.location = "slot_1";
battery.serial_number = "SN12345";
std::cout << "Battery header timestamp: " << battery.header.stamp << "\n";
std::cout << "Battery voltage: " << battery.voltage << " V\n";
std::cout << "Status: " << static_cast<int>(battery.power_supply_status) << "\n";
std::cout << "Serial Number: " << battery.serial_number << "\n";
sensor_msgs::JoyFeedbackArray feedback_array;
feedback_array.array.push_back(sensor_msgs::JoyFeedback{sensor_msgs::JoyFeedback::TYPE_BUZZER, 0, 5000.0f});
std::cout << "First feedback type: " << static_cast<int>(feedback_array.array[0].type) << "\n";
std::cout << "First feedback intensity: " << feedback_array.array[0].intensity << "\n";
sensor_msgs::PointCloud2 cloud;
cloud.header = std_msgs::Header::now("pointcloud_frame");
cloud.width = 100;
cloud.height = 1;
std::cout << "PointCloud2 header frame_id: " << cloud.header.frame_id << "\n";
std::cout << "PointCloud2 header timestamp: " << cloud.header.stamp << "\n";
std::cout << "PointCloud2 width: " << cloud.width << "\n";
std::cout << "PointCloud2 height: " << cloud.height << "\n";
return 0;
}

View File

@ -0,0 +1,16 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 3.16
# Relative path conversion top directories.
set(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/duongtd/robotics_core/common_msgs/std_msgs")
set(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/duongtd/robotics_core/common_msgs/sensor_msgs/test")
# Force unix paths in dependencies.
set(CMAKE_FORCE_UNIX_PATHS 1)
# The C and CXX include file regular expressions for this directory.
set(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$")
set(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$")
set(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN})
set(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN})

View File

@ -0,0 +1 @@
0

View File

@ -0,0 +1,134 @@
# CMAKE generated file: DO NOT EDIT!
# Generated by "Unix Makefiles" Generator, CMake Version 3.16
# Default target executed when no arguments are given to make.
default_target: all
.PHONY : default_target
# Allow only one "make -f Makefile2" at a time, but pass parallelism.
.NOTPARALLEL:
#=============================================================================
# Special targets provided by cmake.
# Disable implicit rules so canonical targets will work.
.SUFFIXES:
# Remove some rules from gmake that .SUFFIXES does not remove.
SUFFIXES =
.SUFFIXES: .hpux_make_needs_suffix_list
# Suppress display of executed commands.
$(VERBOSE).SILENT:
# A target that is always out of date.
cmake_force:
.PHONY : cmake_force
#=============================================================================
# Set environment variables for the build.
# The shell in which to execute make rules.
SHELL = /bin/sh
# The CMake executable.
CMAKE_COMMAND = /usr/bin/cmake
# The command to remove a file.
RM = /usr/bin/cmake -E remove -f
# Escaping for special characters.
EQUALS = =
# The top-level source directory on which CMake was run.
CMAKE_SOURCE_DIR = /home/duongtd/robotics_core/common_msgs/sensor_msgs
# The top-level build directory on which CMake was run.
CMAKE_BINARY_DIR = /home/duongtd/robotics_core/common_msgs/sensor_msgs/test
#=============================================================================
# Targets provided globally by CMake.
# Special rule for the target rebuild_cache
rebuild_cache:
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..."
/usr/bin/cmake -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)
.PHONY : rebuild_cache
# Special rule for the target rebuild_cache
rebuild_cache/fast: rebuild_cache
.PHONY : rebuild_cache/fast
# Special rule for the target edit_cache
edit_cache:
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "No interactive CMake dialog available..."
/usr/bin/cmake -E echo No\ interactive\ CMake\ dialog\ available.
.PHONY : edit_cache
# Special rule for the target edit_cache
edit_cache/fast: edit_cache
.PHONY : edit_cache/fast
# The main all target
all: cmake_check_build_system
cd /home/duongtd/robotics_core/common_msgs/sensor_msgs/test && $(CMAKE_COMMAND) -E cmake_progress_start /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/std_msgs_build/CMakeFiles/progress.marks
cd /home/duongtd/robotics_core/common_msgs/sensor_msgs/test && $(MAKE) -f CMakeFiles/Makefile2 std_msgs_build/all
$(CMAKE_COMMAND) -E cmake_progress_start /home/duongtd/robotics_core/common_msgs/sensor_msgs/test/CMakeFiles 0
.PHONY : all
# The main clean target
clean:
cd /home/duongtd/robotics_core/common_msgs/sensor_msgs/test && $(MAKE) -f CMakeFiles/Makefile2 std_msgs_build/clean
.PHONY : clean
# The main clean target
clean/fast: clean
.PHONY : clean/fast
# Prepare targets for installation.
preinstall: all
cd /home/duongtd/robotics_core/common_msgs/sensor_msgs/test && $(MAKE) -f CMakeFiles/Makefile2 std_msgs_build/preinstall
.PHONY : preinstall
# Prepare targets for installation.
preinstall/fast:
cd /home/duongtd/robotics_core/common_msgs/sensor_msgs/test && $(MAKE) -f CMakeFiles/Makefile2 std_msgs_build/preinstall
.PHONY : preinstall/fast
# clear depends
depend:
cd /home/duongtd/robotics_core/common_msgs/sensor_msgs/test && $(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1
.PHONY : depend
# Help Target
help:
@echo "The following are some of the valid targets for this Makefile:"
@echo "... all (the default if no target is provided)"
@echo "... clean"
@echo "... depend"
@echo "... rebuild_cache"
@echo "... edit_cache"
.PHONY : help
#=============================================================================
# Special targets to cleanup operation of make.
# Special rule to run CMake to check the build system integrity.
# No rule that depends on this can have commands that come from listfiles
# because they might be regenerated.
cmake_check_build_system:
cd /home/duongtd/robotics_core/common_msgs/sensor_msgs/test && $(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0
.PHONY : cmake_check_build_system

View File

@ -0,0 +1,39 @@
# Install script for directory: /home/duongtd/robotics_core/common_msgs/std_msgs
# Set the install prefix
if(NOT DEFINED CMAKE_INSTALL_PREFIX)
set(CMAKE_INSTALL_PREFIX "/usr/local")
endif()
string(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
# Set the install configuration name.
if(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME)
if(BUILD_TYPE)
string(REGEX REPLACE "^[^A-Za-z0-9_]+" ""
CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}")
else()
set(CMAKE_INSTALL_CONFIG_NAME "")
endif()
message(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"")
endif()
# Set the component getting installed.
if(NOT CMAKE_INSTALL_COMPONENT)
if(COMPONENT)
message(STATUS "Install component: \"${COMPONENT}\"")
set(CMAKE_INSTALL_COMPONENT "${COMPONENT}")
else()
set(CMAKE_INSTALL_COMPONENT)
endif()
endif()
# Install shared libraries without execute permission?
if(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE)
set(CMAKE_INSTALL_SO_NO_EXE "1")
endif()
# Is this installation the result of a crosscompile?
if(NOT DEFINED CMAKE_CROSSCOMPILING)
set(CMAKE_CROSSCOMPILING "FALSE")
endif()

Binary file not shown.

7
std_msgs/CMakeLists.txt Normal file
View File

@ -0,0 +1,7 @@
cmake_minimum_required(VERSION 3.10)
project(std_msgs)
set(CMAKE_CXX_STANDARD 17)
add_library(std_msgs INTERFACE)
target_include_directories(std_msgs INTERFACE ${CMAKE_CURRENT_SOURCE_DIR}/include)

View File

@ -0,0 +1,33 @@
#ifndef STD_MSGS_HEADER_H
#define STD_MSGS_HEADER_H
#include <string>
#include <chrono>
#include <cstdint>
namespace std_msgs {
struct Header
{
uint32_t seq = 0; // số thứ tự message
double stamp = 0.0; // thời gian theo giây (Unix time)
std::string frame_id;
Header() = default;
// Hàm tạo nhanh header với timestamp hiện tại
static Header now(const std::string& frame = "")
{
using namespace std::chrono;
double time_now = duration_cast<duration<double>>(system_clock::now().time_since_epoch()).count();
Header h;
h.seq = 0;
h.stamp = time_now;
h.frame_id = frame;
return h;
}
};
} // namespace std_msgs
#endif