Skip to content

Commit

Permalink
Lint
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <[email protected]>
  • Loading branch information
mjcarroll committed May 19, 2023
1 parent 91ddb20 commit 3a66601
Show file tree
Hide file tree
Showing 24 changed files with 161 additions and 84 deletions.
7 changes: 6 additions & 1 deletion compiled/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,16 @@ gz_msgs_generate_messages_impl(
)

gz_add_component(compiled
SOURCES gz.cc
SOURCES src/gz.cc
GET_TARGET_NAME compiled_target)

# Not using target_link_messages because we are registering messages in gz.cc
target_link_libraries(${compiled_target} PRIVATE gz_msgs_msgs)
target_include_directories(${compiled_target} PRIVATE include)

install(
DIRECTORY include/
DESTINATION ${GZ_INCLUDE_INSTALL_DIR_FULL})

##################################################
# Build unit tests
Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
3 changes: 1 addition & 2 deletions compiled/gz.cc → compiled/src/gz.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,14 +25,13 @@
#pragma warning(pop)
#endif

#include "gz.hh"

#include <iostream>
#include <string>
#include <vector>

#include <gz/msgs/config.hh>
#include <gz/msgs/Factory.hh>
#include <gz/msgs/gz.hh>

#include <gz/msgs/MessageTypes.hh>

Expand Down
22 changes: 17 additions & 5 deletions core/include/gz/msgs/Converter.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,32 +26,44 @@ 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);
static void Set(DataT *_data, const MessageT &_msg);

static DataT Convert(const MessageT &_msg){
DataT ret;
Converter<MessageT,DataT>::Set(&ret, _msg);
Converter<MessageT, DataT>::Set(&ret, _msg);
return ret;
}

static MessageT Convert(const DataT &_data){
MessageT ret;
Converter<MessageT,DataT>::Set(&ret, _data);
Converter<MessageT, DataT>::Set(&ret, _data);
return ret;
}
};

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());
Vector3Converter::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
6 changes: 4 additions & 2 deletions core/include/gz/msgs/convert/Color.hh
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,8 @@ inline namespace GZ_MSGS_VERSION_NAMESPACE {

/////////////////////////////////
template<>
inline void Converter<gz::msgs::Color, gz::math::Color>::Set(gz::msgs::Color *_msg, const gz::math::Color &_data)
inline void Converter<gz::msgs::Color, gz::math::Color>::Set(
gz::msgs::Color *_msg, const gz::math::Color &_data)
{
_msg->set_r(_data.R());
_msg->set_g(_data.G());
Expand All @@ -40,7 +41,8 @@ inline void Converter<gz::msgs::Color, gz::math::Color>::Set(gz::msgs::Color *_m
}

template<>
inline void Converter<gz::msgs::Color, gz::math::Color>::Set(gz::math::Color *_data, const gz::msgs::Color &_msg)
inline void Converter<gz::msgs::Color, gz::math::Color>::Set(
gz::math::Color *_data, const gz::msgs::Color &_msg)
{
_data->Set(_msg.r(), _msg.g(), _msg.b(), _msg.a());
}
Expand Down
1 change: 0 additions & 1 deletion core/include/gz/msgs/convert/DiscoveryType.hh
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,6 @@ inline msgs::Discovery::Type ConvertDiscoveryType(const std::string &_str)
/////////////////////////////////////////////
inline std::string ConvertDiscoveryType(const msgs::Discovery::Type &_type)
{
std::string result;
switch (_type)
{
default:
Expand Down
20 changes: 12 additions & 8 deletions core/include/gz/msgs/convert/Inertial.hh
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,8 @@ inline namespace GZ_MSGS_VERSION_NAMESPACE {

/////////////////////////////////
template<>
inline void Converter<gz::msgs::Inertial, gz::math::MassMatrix3d>::Set(gz::msgs::Inertial *_msg, const gz::math::MassMatrix3d &_data)
inline void Converter<gz::msgs::Inertial, gz::math::MassMatrix3d>::Set(
gz::msgs::Inertial *_msg, const gz::math::MassMatrix3d &_data)
{
_msg->set_mass(_data.Mass());
_msg->set_ixx(_data.Ixx());
Expand All @@ -47,7 +48,8 @@ inline void Converter<gz::msgs::Inertial, gz::math::MassMatrix3d>::Set(gz::msgs:
}

template<>
inline void Converter<gz::msgs::Inertial, gz::math::MassMatrix3d>::Set(gz::math::MassMatrix3d *_data, const gz::msgs::Inertial &_msg)
inline void Converter<gz::msgs::Inertial, gz::math::MassMatrix3d>::Set(
gz::math::MassMatrix3d *_data, const gz::msgs::Inertial &_msg)
{
_data->SetMass(_msg.mass());
_data->SetIxx(_msg.ixx());
Expand All @@ -72,10 +74,13 @@ inline gz::math::MassMatrix3d Convert(const gz::msgs::Inertial &_msg)

/////////////////////////////////
template<>
inline void Converter<gz::msgs::Inertial, gz::math::Inertiald>::Set(gz::msgs::Inertial *_msg, const gz::math::Inertiald &_data)
inline void Converter<gz::msgs::Inertial, gz::math::Inertiald>::Set(
gz::msgs::Inertial *_msg, const gz::math::Inertiald &_data)
{
Converter<gz::msgs::Inertial, gz::math::MassMatrix3d>::Set(_msg, _data.MassMatrix());
Converter<gz::msgs::Pose, gz::math::Pose3d>::Set(_msg->mutable_pose(), _data.Pose());
Converter<gz::msgs::Inertial, gz::math::MassMatrix3d>::Set(
_msg, _data.MassMatrix());
Converter<gz::msgs::Pose, gz::math::Pose3d>::Set(
_msg->mutable_pose(), _data.Pose());

if (_data.FluidAddedMass().has_value())
{
Expand Down Expand Up @@ -104,7 +109,8 @@ inline void Converter<gz::msgs::Inertial, gz::math::Inertiald>::Set(gz::msgs::In
}

template<>
inline void Converter<gz::msgs::Inertial, gz::math::Inertiald>::Set(gz::math::Inertiald *_data, const gz::msgs::Inertial &_msg)
inline void Converter<gz::msgs::Inertial, gz::math::Inertiald>::Set(
gz::math::Inertiald *_data, const gz::msgs::Inertial &_msg)
{
gz::math::MassMatrix3d to_set = _data->MassMatrix();
Converter<gz::msgs::Inertial, gz::math::MassMatrix3d>::Set(&to_set, _msg);
Expand Down Expand Up @@ -172,8 +178,6 @@ inline gz::math::Inertiald Convert(const gz::msgs::Inertial &_msg)
{
return Converter<gz::msgs::Inertial, gz::math::Inertiald>::Convert(_msg);
}

} // namespce
} // namespace gz::msgs

#endif // GZ_MSGS_CONVERT_VECTOR3_HH_
9 changes: 6 additions & 3 deletions core/include/gz/msgs/convert/Plane.hh
Original file line number Diff line number Diff line change
Expand Up @@ -33,16 +33,19 @@ inline namespace GZ_MSGS_VERSION_NAMESPACE {

/////////////////////////////////
template<>
inline void Converter<gz::msgs::PlaneGeom, gz::math::Planed>::Set(gz::msgs::PlaneGeom *_msg, const gz::math::Planed &_data)
inline void Converter<gz::msgs::PlaneGeom, gz::math::Planed>::Set(
gz::msgs::PlaneGeom *_msg, const gz::math::Planed &_data)
{
Converter<gz::msgs::Vector3d, gz::math::Vector3d>::Set(_msg->mutable_normal(), _data.Normal());
Converter<gz::msgs::Vector3d, gz::math::Vector3d>::Set(
_msg->mutable_normal(), _data.Normal());
_msg->mutable_size()->set_x(_data.Size().X());
_msg->mutable_size()->set_y(_data.Size().Y());
_msg->set_d(_data.Offset());
}

template<>
inline void Converter<gz::msgs::PlaneGeom, gz::math::Planed>::Set(gz::math::Planed *_data, const gz::msgs::PlaneGeom &_msg)
inline void Converter<gz::msgs::PlaneGeom, gz::math::Planed>::Set(
gz::math::Planed *_data, const gz::msgs::PlaneGeom &_msg)
{
_data->Set(
Converter<gz::msgs::Vector3d, gz::math::Vector3d>::Convert(_msg.normal()),
Expand Down
19 changes: 13 additions & 6 deletions core/include/gz/msgs/convert/Pose.hh
Original file line number Diff line number Diff line change
Expand Up @@ -34,17 +34,24 @@ inline namespace GZ_MSGS_VERSION_NAMESPACE {

/////////////////////////////////
template<>
inline void Converter<gz::msgs::Pose, gz::math::Pose3d>::Set(gz::msgs::Pose *_msg, const gz::math::Pose3d &_data)
inline void Converter<gz::msgs::Pose, gz::math::Pose3d>::Set(
gz::msgs::Pose *_msg, const gz::math::Pose3d &_data)
{
Converter<gz::msgs::Vector3d, gz::math::Vector3d>::Set(_msg->mutable_position(), _data.Pos());
Converter<gz::msgs::Quaternion, gz::math::Quaterniond>::Set(_msg->mutable_orientation(), _data.Rot());
Converter<gz::msgs::Vector3d, gz::math::Vector3d>::Set(
_msg->mutable_position(), _data.Pos());
Converter<gz::msgs::Quaternion, gz::math::Quaterniond>::Set(
_msg->mutable_orientation(), _data.Rot());
}

template<>
inline void Converter<gz::msgs::Pose, gz::math::Pose3d>::Set(gz::math::Pose3d *_data, const gz::msgs::Pose &_msg)
inline void Converter<gz::msgs::Pose, gz::math::Pose3d>::Set(
gz::math::Pose3d *_data, const gz::msgs::Pose &_msg)
{
auto pos = Converter<gz::msgs::Vector3d, gz::math::Vector3d>::Convert(_msg.position());
auto orientation = Converter<gz::msgs::Quaternion, gz::math::Quaterniond>::Convert(_msg.orientation());
auto pos = Converter<gz::msgs::Vector3d, gz::math::Vector3d>::Convert(
_msg.position());
auto orientation =
Converter<gz::msgs::Quaternion, gz::math::Quaterniond>::Convert(
_msg.orientation());
_data->Set(pos, orientation);
}

Expand Down
6 changes: 4 additions & 2 deletions core/include/gz/msgs/convert/Quaternion.hh
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,8 @@ inline namespace GZ_MSGS_VERSION_NAMESPACE {

/////////////////////////////////
template<>
inline void Converter<gz::msgs::Quaternion, gz::math::Quaterniond>::Set(gz::msgs::Quaternion *_msg, const gz::math::Quaterniond &_data)
inline void Converter<gz::msgs::Quaternion, gz::math::Quaterniond>::Set(
gz::msgs::Quaternion *_msg, const gz::math::Quaterniond &_data)
{
_msg->set_w(_data.W());
_msg->set_x(_data.X());
Expand All @@ -40,7 +41,8 @@ inline void Converter<gz::msgs::Quaternion, gz::math::Quaterniond>::Set(gz::msgs
}

template<>
inline void Converter<gz::msgs::Quaternion, gz::math::Quaterniond>::Set(gz::math::Quaterniond *_data, const gz::msgs::Quaternion &_msg)
inline void Converter<gz::msgs::Quaternion, gz::math::Quaterniond>::Set(
gz::math::Quaterniond *_data, const gz::msgs::Quaternion &_msg)
{
_data->Set(_msg.w(), _msg.x(), _msg.y(), _msg.z());
}
Expand Down
25 changes: 16 additions & 9 deletions core/include/gz/msgs/convert/SphericalCoordinates.hh
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,10 @@ inline namespace GZ_MSGS_VERSION_NAMESPACE {

/////////////////////////////////
template<>
inline void Converter<gz::msgs::SphericalCoordinates, gz::math::SphericalCoordinates>::Set(gz::msgs::SphericalCoordinates *_msg, const gz::math::SphericalCoordinates &_data)
inline void
Converter<gz::msgs::SphericalCoordinates, gz::math::SphericalCoordinates>::Set(
gz::msgs::SphericalCoordinates *_msg,
const gz::math::SphericalCoordinates &_data)
{
if (_data.Surface() == math::SphericalCoordinates::EARTH_WGS84)
{
Expand Down Expand Up @@ -62,7 +65,10 @@ inline void Converter<gz::msgs::SphericalCoordinates, gz::math::SphericalCoordin
}

template<>
inline void Converter<gz::msgs::SphericalCoordinates, gz::math::SphericalCoordinates>::Set(gz::math::SphericalCoordinates *_data, const gz::msgs::SphericalCoordinates &_msg)
inline void
Converter<gz::msgs::SphericalCoordinates, gz::math::SphericalCoordinates>::Set(
gz::math::SphericalCoordinates *_data,
const gz::msgs::SphericalCoordinates &_msg)
{
if (_msg.surface_model() == msgs::SphericalCoordinates::EARTH_WGS84)
{
Expand Down Expand Up @@ -100,18 +106,19 @@ inline void Converter<gz::msgs::SphericalCoordinates, gz::math::SphericalCoordin
_data->SetElevationReference(_msg.elevation());
}

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

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


} // namespce
} // namespace gz::msgs

#endif // GZ_MSGS_CONVERT_VECTOR3_HH_
Loading

0 comments on commit 3a66601

Please sign in to comment.