Skip to content

Commit

Permalink
Lint part1
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <mjcarroll@intrinsic.ai>
  • Loading branch information
mjcarroll committed May 18, 2023
1 parent 91ddb20 commit 79041c4
Show file tree
Hide file tree
Showing 5 changed files with 35 additions and 14 deletions.
18 changes: 15 additions & 3 deletions core/include/gz/msgs/Converter.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,11 @@ namespace gz::msgs {
// Inline bracket to help doxygen filtering.
inline namespace GZ_MSGS_VERSION_NAMESPACE {

template <typename MessageT, typename DataT, std::enable_if_t<std::is_base_of_v<google::protobuf::Message, MessageT>, bool> = true>
template <typename MessageT,
typename DataT,
std::enable_if_t<
std::is_base_of_v<
google::protobuf::Message, MessageT>, bool> = true>
struct GZ_MSGS_VISIBLE Converter
{
static void Set(MessageT *_msg, const DataT &_data);
Expand All @@ -45,13 +49,21 @@ struct GZ_MSGS_VISIBLE Converter
}
};

template <typename MessageT, typename DataT, std::enable_if_t<std::is_base_of_v<google::protobuf::Message, MessageT>, bool> = true>
template <typename MessageT,
typename DataT,
std::enable_if_t<
std::is_base_of_v<
google::protobuf::Message, MessageT>, bool> = true>
GZ_MSGS_VISIBLE void Set(MessageT *_msg, const DataT &_data)
{
Converter<MessageT, DataT>::Set(_msg, _data);
}

template <typename MessageT, typename DataT, std::enable_if_t<std::is_base_of_v<google::protobuf::Message, MessageT>, bool> = true>
template <typename MessageT,
typename DataT,
std::enable_if_t<
std::is_base_of_v<
google::protobuf::Message, MessageT>, bool> = true>
GZ_MSGS_VISIBLE void Set(DataT *_data , const MessageT &_msg)
{
Converter<MessageT, DataT>::Set(_data, _msg);
Expand Down
2 changes: 1 addition & 1 deletion core/include/gz/msgs/Factory.hh
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ namespace gz::msgs
inline namespace GZ_MSGS_VERSION_NAMESPACE {

/// \class Factory Factory.hh gz/msgs.hh
/// \brief A global factory that generates protobuf message based on a string type.
/// \brief A factory that generates protobuf message based on a string type.
/// This allows for global registration of messages via static initialization.
/// If you don't need the singleton, consider using MessageFactory instead
class GZ_MSGS_VISIBLE Factory
Expand Down
5 changes: 3 additions & 2 deletions core/include/gz/msgs/MessageFactory.hh
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,9 @@ namespace gz::msgs {

/// \class MessageFactory MessageFactory.hh
/// \brief A factory that generates protobuf message based on a string type.
/// This class will also try to load all Protobuf descriptors in paths provided in
/// LoadDescriptors as well as the GZ_DESCRIPTOR_PATH environment variable.
/// This class will also try to load all Protobuf descriptors in paths
/// provided in LoadDescriptors as well as the GZ_DESCRIPTOR_PATH
/// environment variable.
class GZ_MSGS_VISIBLE MessageFactory
{
/// \brief Base message type
Expand Down
1 change: 1 addition & 0 deletions core/include/gz/msgs/PointCloudPackedUtils.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include <cstdarg>
#include <sstream>
#include <string>
#include <utility>
#include <vector>

#include "gz/msgs/config.hh"
Expand Down
23 changes: 15 additions & 8 deletions core/include/gz/msgs/convert/AxisAlignedBox.hh
Original file line number Diff line number Diff line change
Expand Up @@ -32,27 +32,34 @@ inline namespace GZ_MSGS_VERSION_NAMESPACE {

/////////////////////////////////
template<>
inline void Converter<gz::msgs::AxisAlignedBox, gz::math::AxisAlignedBox>::Set(gz::msgs::AxisAlignedBox *_msg, const gz::math::AxisAlignedBox &_data)
inline void
Converter<gz::msgs::AxisAlignedBox, gz::math::AxisAlignedBox>::Set(
gz::msgs::AxisAlignedBox *_msg, const gz::math::AxisAlignedBox &_data)
{
Converter<gz::msgs::Vector3d, gz::math::Vector3d>::Set(_msg->mutable_min_corner(), _data.Min());
Converter<gz::msgs::Vector3d, gz::math::Vector3d>::Set(_msg->mutable_max_corner(), _data.Max());
using Vector3Converter = Converter<gz::msgs::Vector3d, gz::math::Vector3d>;
Vector3Converter::Set(_msg->mutable_min_corner(), _data.Min());
Vector3Converter::Set(_msg->mutable_max_corner(), _data.Max());
}

template<>
inline void Converter<gz::msgs::AxisAlignedBox, gz::math::AxisAlignedBox>::Set(gz::math::AxisAlignedBox *_data, const gz::msgs::AxisAlignedBox &_msg)
inline void Converter<gz::msgs::AxisAlignedBox, gz::math::AxisAlignedBox>::Set(
gz::math::AxisAlignedBox *_data, const gz::msgs::AxisAlignedBox &_msg)
{
Converter<gz::msgs::Vector3d, gz::math::Vector3d>::Set(&_data->Min(), _msg.min_corner());
Converter<gz::msgs::Vector3d, gz::math::Vector3d>::Set(&_data->Max(), _msg.max_corner());
using Vector3Converter = Converter<gz::msgs::Vector3d, gz::math::Vector3d>;
Vector3Converter::Set(&_data->Min(), _msg.min_corner());
Vctor3Converter::Set(&_data->Max(), _msg.max_corner());
}

inline gz::msgs::AxisAlignedBox Convert(const gz::math::AxisAlignedBox &_data)
{
return Converter<gz::msgs::AxisAlignedBox, gz::math::AxisAlignedBox>::Convert(_data);
return Converter<gz::msgs::AxisAlignedBox,
gz::math::AxisAlignedBox>::Convert(_data);
}

inline gz::math::AxisAlignedBox Convert(const gz::msgs::AxisAlignedBox &_msg)
{
return Converter<gz::msgs::AxisAlignedBox, gz::math::AxisAlignedBox>::Convert(_msg);
return Converter<gz::msgs::AxisAlignedBox,
gz::math::AxisAlignedBox>::Convert(_msg);
}


Expand Down

0 comments on commit 79041c4

Please sign in to comment.