add robot_protocol_msgs

This commit is contained in:
duongtd 2025-12-19 14:41:04 +07:00
parent 6bac684298
commit b3033113ea
14 changed files with 1318 additions and 0 deletions

View File

@ -0,0 +1,36 @@
cmake_minimum_required(VERSION 3.10)
project(robot_protocol_msgs)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
# Thư vin header-only
add_library(robot_protocol_msgs INTERFACE)
# Include path ti thư mc cha file header
target_include_directories(robot_protocol_msgs
INTERFACE
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)
# Liên kết vi std_msgs nếu bn có file Header.h trong include/std_msgs/
target_link_libraries(robot_protocol_msgs INTERFACE)
# --- Cài đt thư vin vào h thng khi chy make install ---
install(TARGETS robot_protocol_msgs
EXPORT robot_protocol_msgs-targets
INCLUDES DESTINATION include # Cài đt include
)
# --- Xut export set costmap_2dTargets thành file CMake module ---
# --- To file lib/cmake/robot_protocol_msgs/costmap_2dTargets.cmake ---
# --- File này cha cu hình giúp project khác có th dùng ---
# --- Find_package(robot_protocol_msgs REQUIRED) ---
# --- Target_link_libraries(my_app PRIVATE robot_protocol_msgs::robot_protocol_msgs) ---
install(EXPORT robot_protocol_msgs-targets
FILE robot_protocol_msgs-targets.cmake
NAMESPACE robot_protocol_msgs::
DESTINATION lib/cmake/robot_protocol_msgs
)

View File

@ -0,0 +1,131 @@
// Generated by gencpp from file robot_protocol_msgs/Action.msg
// DO NOT EDIT!
#ifndef ROBOT_PROTOCOL_MSGS_MESSAGE_ACTION_H
#define ROBOT_PROTOCOL_MSGS_MESSAGE_ACTION_H
#include <string>
#include <vector>
#include <memory>
#include <robot_protocol_msgs/ActionParameter.h>
namespace robot_protocol_msgs
{
template <class ContainerAllocator>
struct Action_
{
typedef Action_<ContainerAllocator> Type;
Action_()
: actionType()
, actionId()
, actionDescription()
, blockingType()
, actionParameters() {
}
Action_(const ContainerAllocator& _alloc)
: actionType(_alloc)
, actionId(_alloc)
, actionDescription(_alloc)
, blockingType(_alloc)
, actionParameters(_alloc) {
(void)_alloc;
}
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _actionType_type;
_actionType_type actionType;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _actionId_type;
_actionId_type actionId;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _actionDescription_type;
_actionDescription_type actionDescription;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _blockingType_type;
_blockingType_type blockingType;
typedef std::vector< ::robot_protocol_msgs::ActionParameter_<ContainerAllocator> , typename std::allocator_traits<ContainerAllocator>::template rebind_alloc< ::robot_protocol_msgs::ActionParameter_<ContainerAllocator> >> _actionParameters_type;
_actionParameters_type actionParameters;
// reducing the odds to have name collisions with Windows.h
#if defined(_WIN32) && defined(NONE)
#undef NONE
#endif
#if defined(_WIN32) && defined(SOFT)
#undef SOFT
#endif
#if defined(_WIN32) && defined(HARD)
#undef HARD
#endif
static const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> NONE;
static const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> SOFT;
static const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> HARD;
typedef boost::shared_ptr< ::robot_protocol_msgs::Action_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Action_<ContainerAllocator> const> ConstPtr;
}; // struct Action_
typedef ::robot_protocol_msgs::Action_<std::allocator<void> > Action;
typedef boost::shared_ptr< ::robot_protocol_msgs::Action > ActionPtr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Action const> ActionConstPtr;
// constants requiring out of line definition
template<typename ContainerAllocator> const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>>
Action_<ContainerAllocator>::NONE =
"NONE"
;
template<typename ContainerAllocator> const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>>
Action_<ContainerAllocator>::SOFT =
"SOFT"
;
template<typename ContainerAllocator> const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>>
Action_<ContainerAllocator>::HARD =
"HARD"
;
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::robot_protocol_msgs::Action_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Action_<ContainerAllocator2> & rhs)
{
return lhs.actionType == rhs.actionType &&
lhs.actionId == rhs.actionId &&
lhs.actionDescription == rhs.actionDescription &&
lhs.blockingType == rhs.blockingType &&
lhs.actionParameters == rhs.actionParameters;
}
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::robot_protocol_msgs::Action_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Action_<ContainerAllocator2> & rhs)
{
return !(lhs == rhs);
}
} // namespace robot_protocol_msgs
#endif // ROBOT_PROTOCOL_MSGS_MESSAGE_ACTION_H

View File

@ -0,0 +1,69 @@
// Generated by gencpp from file robot_protocol_msgs/ActionParameter.msg
// DO NOT EDIT!
#ifndef ROBOT_PROTOCOL_MSGS_MESSAGE_ACTIONPARAMETER_H
#define ROBOT_PROTOCOL_MSGS_MESSAGE_ACTIONPARAMETER_H
#include <string>
#include <vector>
#include <memory>
namespace robot_protocol_msgs
{
template <class ContainerAllocator>
struct ActionParameter_
{
typedef ActionParameter_<ContainerAllocator> Type;
ActionParameter_()
: key()
, value() {
}
ActionParameter_(const ContainerAllocator& _alloc)
: key(_alloc)
, value(_alloc) {
(void)_alloc;
}
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _key_type;
_key_type key;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _value_type;
_value_type value;
typedef boost::shared_ptr< ::robot_protocol_msgs::ActionParameter_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::robot_protocol_msgs::ActionParameter_<ContainerAllocator> const> ConstPtr;
}; // struct ActionParameter_
typedef ::robot_protocol_msgs::ActionParameter_<std::allocator<void> > ActionParameter;
typedef boost::shared_ptr< ::robot_protocol_msgs::ActionParameter > ActionParameterPtr;
typedef boost::shared_ptr< ::robot_protocol_msgs::ActionParameter const> ActionParameterConstPtr;
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::robot_protocol_msgs::ActionParameter_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::ActionParameter_<ContainerAllocator2> & rhs)
{
return lhs.key == rhs.key &&
lhs.value == rhs.value;
}
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::robot_protocol_msgs::ActionParameter_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::ActionParameter_<ContainerAllocator2> & rhs)
{
return !(lhs == rhs);
}
} // namespace robot_protocol_msgs
#endif // ROBOT_PROTOCOL_MSGS_MESSAGE_ACTIONPARAMETER_H

View File

@ -0,0 +1,75 @@
// Generated by gencpp from file robot_protocol_msgs/ControlPoint.msg
// DO NOT EDIT!
#ifndef ROBOT_PROTOCOL_MSGS_MESSAGE_CONTROLPOINT_H
#define ROBOT_PROTOCOL_MSGS_MESSAGE_CONTROLPOINT_H
#include <string>
#include <vector>
#include <memory>
namespace robot_protocol_msgs
{
template <class ContainerAllocator>
struct ControlPoint_
{
typedef ControlPoint_<ContainerAllocator> Type;
ControlPoint_()
: x(0.0)
, y(0.0)
, weight(0.0) {
}
ControlPoint_(const ContainerAllocator& _alloc)
: x(0.0)
, y(0.0)
, weight(0.0) {
(void)_alloc;
}
typedef double _x_type;
_x_type x;
typedef double _y_type;
_y_type y;
typedef double _weight_type;
_weight_type weight;
typedef boost::shared_ptr< ::robot_protocol_msgs::ControlPoint_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::robot_protocol_msgs::ControlPoint_<ContainerAllocator> const> ConstPtr;
}; // struct ControlPoint_
typedef ::robot_protocol_msgs::ControlPoint_<std::allocator<void> > ControlPoint;
typedef boost::shared_ptr< ::robot_protocol_msgs::ControlPoint > ControlPointPtr;
typedef boost::shared_ptr< ::robot_protocol_msgs::ControlPoint const> ControlPointConstPtr;
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::robot_protocol_msgs::ControlPoint_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::ControlPoint_<ContainerAllocator2> & rhs)
{
return lhs.x == rhs.x &&
lhs.y == rhs.y &&
lhs.weight == rhs.weight;
}
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::robot_protocol_msgs::ControlPoint_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::ControlPoint_<ContainerAllocator2> & rhs)
{
return !(lhs == rhs);
}
} // namespace robot_protocol_msgs
#endif // ROBOT_PROTOCOL_MSGS_MESSAGE_CONTROLPOINT_H

View File

@ -0,0 +1,192 @@
// Generated by gencpp from file robot_protocol_msgs/Edge.msg
// DO NOT EDIT!
#ifndef ROBOT_PROTOCOL_MSGS_MESSAGE_EDGE_H
#define ROBOT_PROTOCOL_MSGS_MESSAGE_EDGE_H
#include <string>
#include <vector>
#include <memory>
#include <robot_protocol_msgs/Trajectory.h>
#include <robot_protocol_msgs/Action.h>
namespace robot_protocol_msgs
{
template <class ContainerAllocator>
struct Edge_
{
typedef Edge_<ContainerAllocator> Type;
Edge_()
: edgeId()
, sequenceId(0)
, edgeDescription()
, released(false)
, startNodeId()
, endNodeId()
, maxSpeed(0.0)
, maxHeight(0.0)
, minHeight(0.0)
, orientation(0.0)
, orientationType()
, direction()
, rotationAllowed(false)
, maxRotationSpeed(0.0)
, trajectory()
, length(0.0)
, actions() {
}
Edge_(const ContainerAllocator& _alloc)
: edgeId(_alloc)
, sequenceId(0)
, edgeDescription(_alloc)
, released(false)
, startNodeId(_alloc)
, endNodeId(_alloc)
, maxSpeed(0.0)
, maxHeight(0.0)
, minHeight(0.0)
, orientation(0.0)
, orientationType(_alloc)
, direction(_alloc)
, rotationAllowed(false)
, maxRotationSpeed(0.0)
, trajectory(_alloc)
, length(0.0)
, actions(_alloc) {
(void)_alloc;
}
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _edgeId_type;
_edgeId_type edgeId;
typedef int32_t _sequenceId_type;
_sequenceId_type sequenceId;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _edgeDescription_type;
_edgeDescription_type edgeDescription;
typedef uint8_t _released_type;
_released_type released;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _startNodeId_type;
_startNodeId_type startNodeId;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _endNodeId_type;
_endNodeId_type endNodeId;
typedef double _maxSpeed_type;
_maxSpeed_type maxSpeed;
typedef double _maxHeight_type;
_maxHeight_type maxHeight;
typedef double _minHeight_type;
_minHeight_type minHeight;
typedef double _orientation_type;
_orientation_type orientation;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _orientationType_type;
_orientationType_type orientationType;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _direction_type;
_direction_type direction;
typedef uint8_t _rotationAllowed_type;
_rotationAllowed_type rotationAllowed;
typedef double _maxRotationSpeed_type;
_maxRotationSpeed_type maxRotationSpeed;
typedef ::robot_protocol_msgs::Trajectory_<ContainerAllocator> _trajectory_type;
_trajectory_type trajectory;
typedef double _length_type;
_length_type length;
typedef std::vector< ::robot_protocol_msgs::Action_<ContainerAllocator> , typename std::allocator_traits<ContainerAllocator>::template rebind_alloc< ::robot_protocol_msgs::Action_<ContainerAllocator> >> _actions_type;
_actions_type actions;
// reducing the odds to have name collisions with Windows.h
#if defined(_WIN32) && defined(GLOBAL)
#undef GLOBAL
#endif
#if defined(_WIN32) && defined(TANGENTIAL)
#undef TANGENTIAL
#endif
static const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> GLOBAL;
static const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> TANGENTIAL;
typedef boost::shared_ptr< ::robot_protocol_msgs::Edge_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Edge_<ContainerAllocator> const> ConstPtr;
}; // struct Edge_
typedef ::robot_protocol_msgs::Edge_<std::allocator<void> > Edge;
typedef boost::shared_ptr< ::robot_protocol_msgs::Edge > EdgePtr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Edge const> EdgeConstPtr;
// constants requiring out of line definition
template<typename ContainerAllocator> const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>>
Edge_<ContainerAllocator>::GLOBAL =
"GLOBAL"
;
template<typename ContainerAllocator> const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>>
Edge_<ContainerAllocator>::TANGENTIAL =
"TANGENTIAL"
;
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::robot_protocol_msgs::Edge_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Edge_<ContainerAllocator2> & rhs)
{
return lhs.edgeId == rhs.edgeId &&
lhs.sequenceId == rhs.sequenceId &&
lhs.edgeDescription == rhs.edgeDescription &&
lhs.released == rhs.released &&
lhs.startNodeId == rhs.startNodeId &&
lhs.endNodeId == rhs.endNodeId &&
lhs.maxSpeed == rhs.maxSpeed &&
lhs.maxHeight == rhs.maxHeight &&
lhs.minHeight == rhs.minHeight &&
lhs.orientation == rhs.orientation &&
lhs.orientationType == rhs.orientationType &&
lhs.direction == rhs.direction &&
lhs.rotationAllowed == rhs.rotationAllowed &&
lhs.maxRotationSpeed == rhs.maxRotationSpeed &&
lhs.trajectory == rhs.trajectory &&
lhs.length == rhs.length &&
lhs.actions == rhs.actions;
}
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::robot_protocol_msgs::Edge_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Edge_<ContainerAllocator2> & rhs)
{
return !(lhs == rhs);
}
} // namespace robot_protocol_msgs
#endif // ROBOT_PROTOCOL_MSGS_MESSAGE_EDGE_H

View File

@ -0,0 +1,112 @@
// Generated by gencpp from file robot_protocol_msgs/Error.msg
// DO NOT EDIT!
#ifndef ROBOT_PROTOCOL_MSGS_MESSAGE_ERROR_H
#define ROBOT_PROTOCOL_MSGS_MESSAGE_ERROR_H
#include <string>
#include <vector>
#include <memory>
#include <robot_protocol_msgs/ErrorReference.h>
namespace robot_protocol_msgs
{
template <class ContainerAllocator>
struct Error_
{
typedef Error_<ContainerAllocator> Type;
Error_()
: errorType()
, errorReferences()
, errorDescription()
, errorLevel() {
}
Error_(const ContainerAllocator& _alloc)
: errorType(_alloc)
, errorReferences(_alloc)
, errorDescription(_alloc)
, errorLevel(_alloc) {
(void)_alloc;
}
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _errorType_type;
_errorType_type errorType;
typedef std::vector< ::robot_protocol_msgs::ErrorReference_<ContainerAllocator> , typename std::allocator_traits<ContainerAllocator>::template rebind_alloc< ::robot_protocol_msgs::ErrorReference_<ContainerAllocator> >> _errorReferences_type;
_errorReferences_type errorReferences;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _errorDescription_type;
_errorDescription_type errorDescription;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _errorLevel_type;
_errorLevel_type errorLevel;
// reducing the odds to have name collisions with Windows.h
#if defined(_WIN32) && defined(WARNING)
#undef WARNING
#endif
#if defined(_WIN32) && defined(FATAL)
#undef FATAL
#endif
static const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> WARNING;
static const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> FATAL;
typedef boost::shared_ptr< ::robot_protocol_msgs::Error_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Error_<ContainerAllocator> const> ConstPtr;
}; // struct Error_
typedef ::robot_protocol_msgs::Error_<std::allocator<void> > Error;
typedef boost::shared_ptr< ::robot_protocol_msgs::Error > ErrorPtr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Error const> ErrorConstPtr;
// constants requiring out of line definition
template<typename ContainerAllocator> const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>>
Error_<ContainerAllocator>::WARNING =
"WARNING"
;
template<typename ContainerAllocator> const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>>
Error_<ContainerAllocator>::FATAL =
"FATAL"
;
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::robot_protocol_msgs::Error_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Error_<ContainerAllocator2> & rhs)
{
return lhs.errorType == rhs.errorType &&
lhs.errorReferences == rhs.errorReferences &&
lhs.errorDescription == rhs.errorDescription &&
lhs.errorLevel == rhs.errorLevel;
}
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::robot_protocol_msgs::Error_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Error_<ContainerAllocator2> & rhs)
{
return !(lhs == rhs);
}
} // namespace robot_protocol_msgs
#endif // ROBOT_PROTOCOL_MSGS_MESSAGE_ERROR_H

View File

@ -0,0 +1,68 @@
// Generated by gencpp from file robot_protocol_msgs/ErrorReference.msg
// DO NOT EDIT!
#ifndef ROBOT_PROTOCOL_MSGS_MESSAGE_ERRORREFERENCE_H
#define ROBOT_PROTOCOL_MSGS_MESSAGE_ERRORREFERENCE_H
#include <string>
#include <vector>
#include <memory>
namespace robot_protocol_msgs
{
template <class ContainerAllocator>
struct ErrorReference_
{
typedef ErrorReference_<ContainerAllocator> Type;
ErrorReference_()
: referenceKey()
, referenceValue() {
}
ErrorReference_(const ContainerAllocator& _alloc)
: referenceKey(_alloc)
, referenceValue(_alloc) {
(void)_alloc;
}
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _referenceKey_type;
_referenceKey_type referenceKey;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _referenceValue_type;
_referenceValue_type referenceValue;
typedef boost::shared_ptr< ::robot_protocol_msgs::ErrorReference_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::robot_protocol_msgs::ErrorReference_<ContainerAllocator> const> ConstPtr;
}; // struct ErrorReference_
typedef ::robot_protocol_msgs::ErrorReference_<std::allocator<void> > ErrorReference;
typedef boost::shared_ptr< ::robot_protocol_msgs::ErrorReference > ErrorReferencePtr;
typedef boost::shared_ptr< ::robot_protocol_msgs::ErrorReference const> ErrorReferenceConstPtr;
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::robot_protocol_msgs::ErrorReference_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::ErrorReference_<ContainerAllocator2> & rhs)
{
return lhs.referenceKey == rhs.referenceKey &&
lhs.referenceValue == rhs.referenceValue;
}
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::robot_protocol_msgs::ErrorReference_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::ErrorReference_<ContainerAllocator2> & rhs)
{
return !(lhs == rhs);
}
} // namespace robot_protocol_msgs
#endif // ROBOT_PROTOCOL_MSGS_MESSAGE_ERRORREFERENCE_H

View File

@ -0,0 +1,112 @@
// Generated by gencpp from file robot_protocol_msgs/Info.msg
// DO NOT EDIT!
#ifndef ROBOT_PROTOCOL_MSGS_MESSAGE_INFO_H
#define ROBOT_PROTOCOL_MSGS_MESSAGE_INFO_H
#include <string>
#include <vector>
#include <memory>
#include <robot_protocol_msgs/InfoReference.h>
namespace robot_protocol_msgs
{
template <class ContainerAllocator>
struct Info_
{
typedef Info_<ContainerAllocator> Type;
Info_()
: infoType()
, infoReferences()
, infoDescription()
, infoLevel() {
}
Info_(const ContainerAllocator& _alloc)
: infoType(_alloc)
, infoReferences(_alloc)
, infoDescription(_alloc)
, infoLevel(_alloc) {
(void)_alloc;
}
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _infoType_type;
_infoType_type infoType;
typedef std::vector< ::robot_protocol_msgs::InfoReference_<ContainerAllocator> , typename std::allocator_traits<ContainerAllocator>::template rebind_alloc< ::robot_protocol_msgs::InfoReference_<ContainerAllocator> >> _infoReferences_type;
_infoReferences_type infoReferences;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _infoDescription_type;
_infoDescription_type infoDescription;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _infoLevel_type;
_infoLevel_type infoLevel;
// reducing the odds to have name collisions with Windows.h
#if defined(_WIN32) && defined(DEBUG)
#undef DEBUG
#endif
#if defined(_WIN32) && defined(INFO)
#undef INFO
#endif
static const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> DEBUG;
static const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> INFO;
typedef boost::shared_ptr< ::robot_protocol_msgs::Info_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Info_<ContainerAllocator> const> ConstPtr;
}; // struct Info_
typedef ::robot_protocol_msgs::Info_<std::allocator<void> > Info;
typedef boost::shared_ptr< ::robot_protocol_msgs::Info > InfoPtr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Info const> InfoConstPtr;
// constants requiring out of line definition
template<typename ContainerAllocator> const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>>
Info_<ContainerAllocator>::DEBUG =
"DEBUG"
;
template<typename ContainerAllocator> const std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>>
Info_<ContainerAllocator>::INFO =
"INFO"
;
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::robot_protocol_msgs::Info_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Info_<ContainerAllocator2> & rhs)
{
return lhs.infoType == rhs.infoType &&
lhs.infoReferences == rhs.infoReferences &&
lhs.infoDescription == rhs.infoDescription &&
lhs.infoLevel == rhs.infoLevel;
}
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::robot_protocol_msgs::Info_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Info_<ContainerAllocator2> & rhs)
{
return !(lhs == rhs);
}
} // namespace robot_protocol_msgs
#endif // ROBOT_PROTOCOL_MSGS_MESSAGE_INFO_H

View File

@ -0,0 +1,69 @@
// Generated by gencpp from file robot_protocol_msgs/InfoReference.msg
// DO NOT EDIT!
#ifndef ROBOT_PROTOCOL_MSGS_MESSAGE_INFOREFERENCE_H
#define ROBOT_PROTOCOL_MSGS_MESSAGE_INFOREFERENCE_H
#include <string>
#include <vector>
#include <memory>
namespace robot_protocol_msgs
{
template <class ContainerAllocator>
struct InfoReference_
{
typedef InfoReference_<ContainerAllocator> Type;
InfoReference_()
: referenceKey()
, referenceValue() {
}
InfoReference_(const ContainerAllocator& _alloc)
: referenceKey(_alloc)
, referenceValue(_alloc) {
(void)_alloc;
}
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _referenceKey_type;
_referenceKey_type referenceKey;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _referenceValue_type;
_referenceValue_type referenceValue;
typedef boost::shared_ptr< ::robot_protocol_msgs::InfoReference_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::robot_protocol_msgs::InfoReference_<ContainerAllocator> const> ConstPtr;
}; // struct InfoReference_
typedef ::robot_protocol_msgs::InfoReference_<std::allocator<void> > InfoReference;
typedef boost::shared_ptr< ::robot_protocol_msgs::InfoReference > InfoReferencePtr;
typedef boost::shared_ptr< ::robot_protocol_msgs::InfoReference const> InfoReferenceConstPtr;
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::robot_protocol_msgs::InfoReference_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::InfoReference_<ContainerAllocator2> & rhs)
{
return lhs.referenceKey == rhs.referenceKey &&
lhs.referenceValue == rhs.referenceValue;
}
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::robot_protocol_msgs::InfoReference_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::InfoReference_<ContainerAllocator2> & rhs)
{
return !(lhs == rhs);
}
} // namespace robot_protocol_msgs
#endif // ROBOT_PROTOCOL_MSGS_MESSAGE_INFOREFERENCE_H

View File

@ -0,0 +1,64 @@
// Generated by gencpp from file robot_protocol_msgs/Information.msg
// DO NOT EDIT!
#ifndef ROBOT_PROTOCOL_MSGS_MESSAGE_INFORMATION_H
#define ROBOT_PROTOCOL_MSGS_MESSAGE_INFORMATION_H
#include <string>
#include <vector>
#include <memory>
#include <robot_protocol_msgs/Info.h>
namespace robot_protocol_msgs
{
template <class ContainerAllocator>
struct Information_
{
typedef Information_<ContainerAllocator> Type;
Information_()
: information() {
}
Information_(const ContainerAllocator& _alloc)
: information(_alloc) {
(void)_alloc;
}
typedef std::vector< ::robot_protocol_msgs::Info_<ContainerAllocator> , typename std::allocator_traits<ContainerAllocator>::template rebind_alloc< ::robot_protocol_msgs::Info_<ContainerAllocator> >> _information_type;
_information_type information;
typedef boost::shared_ptr< ::robot_protocol_msgs::Information_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Information_<ContainerAllocator> const> ConstPtr;
}; // struct Information_
typedef ::robot_protocol_msgs::Information_<std::allocator<void> > Information;
typedef boost::shared_ptr< ::robot_protocol_msgs::Information > InformationPtr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Information const> InformationConstPtr;
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::robot_protocol_msgs::Information_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Information_<ContainerAllocator2> & rhs)
{
return lhs.information == rhs.information;
}
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::robot_protocol_msgs::Information_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Information_<ContainerAllocator2> & rhs)
{
return !(lhs == rhs);
}
} // namespace robot_protocol_msgs
#endif // ROBOT_PROTOCOL_MSGS_MESSAGE_INFORMATION_H

View File

@ -0,0 +1,95 @@
// Generated by gencpp from file robot_protocol_msgs/Node.msg
// DO NOT EDIT!
#ifndef ROBOT_PROTOCOL_MSGS_MESSAGE_NODE_H
#define ROBOT_PROTOCOL_MSGS_MESSAGE_NODE_H
#include <string>
#include <vector>
#include <memory>
#include <robot_protocol_msgs/NodePosition.h>
#include <robot_protocol_msgs/Action.h>
namespace robot_protocol_msgs
{
template <class ContainerAllocator>
struct Node_
{
typedef Node_<ContainerAllocator> Type;
Node_()
: nodeId()
, sequenceId(0)
, nodeDescription()
, released(false)
, nodePosition()
, actions() {
}
Node_(const ContainerAllocator& _alloc)
: nodeId(_alloc)
, sequenceId(0)
, nodeDescription(_alloc)
, released(false)
, nodePosition(_alloc)
, actions(_alloc) {
(void)_alloc;
}
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _nodeId_type;
_nodeId_type nodeId;
typedef int32_t _sequenceId_type;
_sequenceId_type sequenceId;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _nodeDescription_type;
_nodeDescription_type nodeDescription;
typedef uint8_t _released_type;
_released_type released;
typedef ::robot_protocol_msgs::NodePosition_<ContainerAllocator> _nodePosition_type;
_nodePosition_type nodePosition;
typedef std::vector< ::robot_protocol_msgs::Action_<ContainerAllocator> , typename std::allocator_traits<ContainerAllocator>::template rebind_alloc< ::robot_protocol_msgs::Action_<ContainerAllocator> >> _actions_type;
_actions_type actions;
typedef boost::shared_ptr< ::robot_protocol_msgs::Node_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Node_<ContainerAllocator> const> ConstPtr;
}; // struct Node_
typedef ::robot_protocol_msgs::Node_<std::allocator<void> > Node;
typedef boost::shared_ptr< ::robot_protocol_msgs::Node > NodePtr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Node const> NodeConstPtr;
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::robot_protocol_msgs::Node_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Node_<ContainerAllocator2> & rhs)
{
return lhs.nodeId == rhs.nodeId &&
lhs.sequenceId == rhs.sequenceId &&
lhs.nodeDescription == rhs.nodeDescription &&
lhs.released == rhs.released &&
lhs.nodePosition == rhs.nodePosition &&
lhs.actions == rhs.actions;
}
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::robot_protocol_msgs::Node_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Node_<ContainerAllocator2> & rhs)
{
return !(lhs == rhs);
}
} // namespace robot_protocol_msgs
#endif // ROBOT_PROTOCOL_MSGS_MESSAGE_NODE_H

View File

@ -0,0 +1,99 @@
// Generated by gencpp from file robot_protocol_msgs/NodePosition.msg
// DO NOT EDIT!
#ifndef ROBOT_PROTOCOL_MSGS_MESSAGE_NODEPOSITION_H
#define ROBOT_PROTOCOL_MSGS_MESSAGE_NODEPOSITION_H
#include <string>
#include <vector>
#include <memory>
namespace robot_protocol_msgs
{
template <class ContainerAllocator>
struct NodePosition_
{
typedef NodePosition_<ContainerAllocator> Type;
NodePosition_()
: x(0.0)
, y(0.0)
, theta(0.0)
, allowedDeviationXY(0.0)
, allowedDeviationTheta(0.0)
, mapId()
, mapDescription() {
}
NodePosition_(const ContainerAllocator& _alloc)
: x(0.0)
, y(0.0)
, theta(0.0)
, allowedDeviationXY(0.0)
, allowedDeviationTheta(0.0)
, mapId(_alloc)
, mapDescription(_alloc) {
(void)_alloc;
}
typedef double _x_type;
_x_type x;
typedef double _y_type;
_y_type y;
typedef double _theta_type;
_theta_type theta;
typedef float _allowedDeviationXY_type;
_allowedDeviationXY_type allowedDeviationXY;
typedef float _allowedDeviationTheta_type;
_allowedDeviationTheta_type allowedDeviationTheta;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _mapId_type;
_mapId_type mapId;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _mapDescription_type;
_mapDescription_type mapDescription;
typedef boost::shared_ptr< ::robot_protocol_msgs::NodePosition_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::robot_protocol_msgs::NodePosition_<ContainerAllocator> const> ConstPtr;
}; // struct NodePosition_
typedef ::robot_protocol_msgs::NodePosition_<std::allocator<void> > NodePosition;
typedef boost::shared_ptr< ::robot_protocol_msgs::NodePosition > NodePositionPtr;
typedef boost::shared_ptr< ::robot_protocol_msgs::NodePosition const> NodePositionConstPtr;
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::robot_protocol_msgs::NodePosition_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::NodePosition_<ContainerAllocator2> & rhs)
{
return lhs.x == rhs.x &&
lhs.y == rhs.y &&
lhs.theta == rhs.theta &&
lhs.allowedDeviationXY == rhs.allowedDeviationXY &&
lhs.allowedDeviationTheta == rhs.allowedDeviationTheta &&
lhs.mapId == rhs.mapId &&
lhs.mapDescription == rhs.mapDescription;
}
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::robot_protocol_msgs::NodePosition_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::NodePosition_<ContainerAllocator2> & rhs)
{
return !(lhs == rhs);
}
} // namespace robot_protocol_msgs
#endif // ROBOT_PROTOCOL_MSGS_MESSAGE_NODEPOSITION_H

View File

@ -0,0 +1,120 @@
// Generated by gencpp from file robot_protocol_msgs/Order.msg
// DO NOT EDIT!
#ifndef ROBOT_PROTOCOL_MSGS_MESSAGE_ORDER_H
#define ROBOT_PROTOCOL_MSGS_MESSAGE_ORDER_H
#include <string>
#include <vector>
#include <memory>
#include <robot_protocol_msgs/Node.h>
#include <robot_protocol_msgs/Edge.h>
namespace robot_protocol_msgs
{
template <class ContainerAllocator>
struct Order_
{
typedef Order_<ContainerAllocator> Type;
Order_()
: headerId(0)
, timestamp()
, version()
, manufacturer()
, serialNumber()
, orderId()
, orderUpdateId(0)
, nodes()
, edges()
, zoneSetId() {
}
Order_(const ContainerAllocator& _alloc)
: headerId(0)
, timestamp(_alloc)
, version(_alloc)
, manufacturer(_alloc)
, serialNumber(_alloc)
, orderId(_alloc)
, orderUpdateId(0)
, nodes(_alloc)
, edges(_alloc)
, zoneSetId(_alloc) {
(void)_alloc;
}
typedef int32_t _headerId_type;
_headerId_type headerId;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _timestamp_type;
_timestamp_type timestamp;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _version_type;
_version_type version;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _manufacturer_type;
_manufacturer_type manufacturer;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _serialNumber_type;
_serialNumber_type serialNumber;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _orderId_type;
_orderId_type orderId;
typedef uint32_t _orderUpdateId_type;
_orderUpdateId_type orderUpdateId;
typedef std::vector< ::robot_protocol_msgs::Node_<ContainerAllocator> , typename std::allocator_traits<ContainerAllocator>::template rebind_alloc< ::robot_protocol_msgs::Node_<ContainerAllocator> >> _nodes_type;
_nodes_type nodes;
typedef std::vector< ::robot_protocol_msgs::Edge_<ContainerAllocator> , typename std::allocator_traits<ContainerAllocator>::template rebind_alloc< ::robot_protocol_msgs::Edge_<ContainerAllocator> >> _edges_type;
_edges_type edges;
typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>> _zoneSetId_type;
_zoneSetId_type zoneSetId;
typedef boost::shared_ptr< ::robot_protocol_msgs::Order_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Order_<ContainerAllocator> const> ConstPtr;
}; // struct Order_
typedef ::robot_protocol_msgs::Order_<std::allocator<void> > Order;
typedef boost::shared_ptr< ::robot_protocol_msgs::Order > OrderPtr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Order const> OrderConstPtr;
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::robot_protocol_msgs::Order_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Order_<ContainerAllocator2> & rhs)
{
return lhs.headerId == rhs.headerId &&
lhs.timestamp == rhs.timestamp &&
lhs.version == rhs.version &&
lhs.manufacturer == rhs.manufacturer &&
lhs.serialNumber == rhs.serialNumber &&
lhs.orderId == rhs.orderId &&
lhs.orderUpdateId == rhs.orderUpdateId &&
lhs.nodes == rhs.nodes &&
lhs.edges == rhs.edges &&
lhs.zoneSetId == rhs.zoneSetId;
}
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::robot_protocol_msgs::Order_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Order_<ContainerAllocator2> & rhs)
{
return !(lhs == rhs);
}
} // namespace robot_protocol_msgs
#endif // ROBOT_PROTOCOL_MSGS_MESSAGE_ORDER_H

View File

@ -0,0 +1,76 @@
// Generated by gencpp from file robot_protocol_msgs/Trajectory.msg
// DO NOT EDIT!
#ifndef ROBOT_PROTOCOL_MSGS_MESSAGE_TRAJECTORY_H
#define ROBOT_PROTOCOL_MSGS_MESSAGE_TRAJECTORY_H
#include <string>
#include <vector>
#include <memory>
#include <robot_protocol_msgs/ControlPoint.h>
namespace robot_protocol_msgs
{
template <class ContainerAllocator>
struct Trajectory_
{
typedef Trajectory_<ContainerAllocator> Type;
Trajectory_()
: degree(0)
, knotVector()
, controlPoints() {
}
Trajectory_(const ContainerAllocator& _alloc)
: degree(0)
, knotVector(_alloc)
, controlPoints(_alloc) {
(void)_alloc;
}
typedef uint32_t _degree_type;
_degree_type degree;
typedef std::vector<double, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<double>> _knotVector_type;
_knotVector_type knotVector;
typedef std::vector< ::robot_protocol_msgs::ControlPoint_<ContainerAllocator> , typename std::allocator_traits<ContainerAllocator>::template rebind_alloc< ::robot_protocol_msgs::ControlPoint_<ContainerAllocator> >> _controlPoints_type;
_controlPoints_type controlPoints;
typedef boost::shared_ptr< ::robot_protocol_msgs::Trajectory_<ContainerAllocator> > Ptr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Trajectory_<ContainerAllocator> const> ConstPtr;
}; // struct Trajectory_
typedef ::robot_protocol_msgs::Trajectory_<std::allocator<void> > Trajectory;
typedef boost::shared_ptr< ::robot_protocol_msgs::Trajectory > TrajectoryPtr;
typedef boost::shared_ptr< ::robot_protocol_msgs::Trajectory const> TrajectoryConstPtr;
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator==(const ::robot_protocol_msgs::Trajectory_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Trajectory_<ContainerAllocator2> & rhs)
{
return lhs.degree == rhs.degree &&
lhs.knotVector == rhs.knotVector &&
lhs.controlPoints == rhs.controlPoints;
}
template<typename ContainerAllocator1, typename ContainerAllocator2>
bool operator!=(const ::robot_protocol_msgs::Trajectory_<ContainerAllocator1> & lhs, const ::robot_protocol_msgs::Trajectory_<ContainerAllocator2> & rhs)
{
return !(lhs == rhs);
}
} // namespace robot_protocol_msgs
#endif // ROBOT_PROTOCOL_MSGS_MESSAGE_TRAJECTORY_H