Skip to content

Commit

Permalink
Drop template from conversions
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <[email protected]>
  • Loading branch information
mjcarroll committed Jun 23, 2023
1 parent 7c67fe5 commit 5fc7a7e
Show file tree
Hide file tree
Showing 14 changed files with 178 additions and 312 deletions.
74 changes: 0 additions & 74 deletions core/include/gz/msgs/Converter.hh

This file was deleted.

34 changes: 14 additions & 20 deletions core/include/gz/msgs/convert/AxisAlignedBox.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#ifndef GZ_MSGS_CONVERT_AXISALIGNEDBOX_HH_
#define GZ_MSGS_CONVERT_AXISALIGNEDBOX_HH_

#include <gz/msgs/Converter.hh>
#include <gz/msgs/convert/Vector3.hh>

// Message Headers
Expand All @@ -31,38 +30,33 @@ namespace gz::msgs {
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 Set(gz::msgs::AxisAlignedBox *_msg,
const gz::math::AxisAlignedBox &_data)
{
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());
Set(_msg->mutable_min_corner(), _data.Min());
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 Set(gz::math::AxisAlignedBox *_data,
const gz::msgs::AxisAlignedBox &_msg)
{
using Vector3Converter = Converter<gz::msgs::Vector3d, gz::math::Vector3d>;
Vector3Converter::Set(&_data->Min(), _msg.min_corner());
Vector3Converter::Set(&_data->Max(), _msg.max_corner());
Set(&_data->Min(), _msg.min_corner());
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);
gz::msgs::AxisAlignedBox ret;
Set(&ret, _data);
return ret;
}

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


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

Expand Down
20 changes: 8 additions & 12 deletions core/include/gz/msgs/convert/Color.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,6 @@
#ifndef GZ_MSGS_CONVERT_COLOR_HH_
#define GZ_MSGS_CONVERT_COLOR_HH_

#include <gz/msgs/Converter.hh>

// Message Headers
#include "gz/msgs/color.pb.h"

Expand All @@ -30,34 +28,32 @@ namespace gz::msgs {
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 Set(gz::msgs::Color *_msg, const gz::math::Color &_data)
{
_msg->set_r(_data.R());
_msg->set_g(_data.G());
_msg->set_b(_data.B());
_msg->set_a(_data.A());
}

template<>
inline void Converter<gz::msgs::Color, gz::math::Color>::Set(
gz::math::Color *_data, const gz::msgs::Color &_msg)
inline void Set(gz::math::Color *_data, const gz::msgs::Color &_msg)
{
_data->Set(_msg.r(), _msg.g(), _msg.b(), _msg.a());
}

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

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


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

Expand Down
2 changes: 0 additions & 2 deletions core/include/gz/msgs/convert/DiscoveryType.hh
Original file line number Diff line number Diff line change
Expand Up @@ -116,8 +116,6 @@ inline std::string ToString(const msgs::Discovery::Type &_t)
{
return ConvertDiscoveryType(_t);
}


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

Expand Down
5 changes: 2 additions & 3 deletions core/include/gz/msgs/convert/FuelMetadata.hh
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ inline namespace GZ_MSGS_VERSION_NAMESPACE {

/////////////////////////////////////////////////
inline bool ConvertFuelMetadata(const std::string &_modelConfigStr,
msgs::FuelMetadata &_meta)
msgs::FuelMetadata &_meta)
{
gz::msgs::FuelMetadata meta;

Expand Down Expand Up @@ -184,7 +184,7 @@ inline bool ConvertFuelMetadata(const std::string &_modelConfigStr,

/////////////////////////////////////////////////
inline bool ConvertFuelMetadata(const msgs::FuelMetadata &_meta,
std::string &_modelConfigStr)
std::string &_modelConfigStr)
{
std::ostringstream out;

Expand Down Expand Up @@ -252,7 +252,6 @@ inline bool ConvertFuelMetadata(const msgs::FuelMetadata &_meta,
_modelConfigStr = out.str();
return true;
}

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

Expand Down
1 change: 0 additions & 1 deletion core/include/gz/msgs/convert/GeometryType.hh
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,6 @@ inline std::string ConvertGeometryType(const msgs::Geometry::Type _type)
}
return result;
}

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

Expand Down
46 changes: 17 additions & 29 deletions core/include/gz/msgs/convert/Inertial.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#ifndef GZ_MSGS_CONVERT_INERTIAL_HH_
#define GZ_MSGS_CONVERT_INERTIAL_HH_

#include <gz/msgs/Converter.hh>
#include <gz/msgs/convert/Pose.hh>
#include <gz/msgs/convert/Vector3.hh>

Expand All @@ -33,9 +32,7 @@ namespace gz::msgs {
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 Set(gz::msgs::Inertial *_msg, const gz::math::MassMatrix3d &_data)
{
_msg->set_mass(_data.Mass());
_msg->set_ixx(_data.Ixx());
Expand All @@ -47,9 +44,7 @@ inline void Converter<gz::msgs::Inertial, gz::math::MassMatrix3d>::Set(
_msg->mutable_pose()->mutable_orientation()->set_w(1);
}

template<>
inline void Converter<gz::msgs::Inertial, gz::math::MassMatrix3d>::Set(
gz::math::MassMatrix3d *_data, const gz::msgs::Inertial &_msg)
inline void Set(gz::math::MassMatrix3d *_data, const gz::msgs::Inertial &_msg)
{
_data->SetMass(_msg.mass());
_data->SetIxx(_msg.ixx());
Expand All @@ -62,25 +57,16 @@ inline void Converter<gz::msgs::Inertial, gz::math::MassMatrix3d>::Set(

inline gz::msgs::Inertial Convert(const gz::math::MassMatrix3d &_data)
{
return Converter<gz::msgs::Inertial, gz::math::MassMatrix3d>::Convert(_data);
gz::msgs::Inertial ret;
Set(&ret, _data);
return ret;
}

/*
inline gz::math::MassMatrix3d Convert(const gz::msgs::Inertial &_msg)
{
return Converter<gz::msgs::Inertial, gz::math::MassMatrix3d>::Convert(_msg);
}
*/

/////////////////////////////////
template<>
inline void Converter<gz::msgs::Inertial, gz::math::Inertiald>::Set(
gz::msgs::Inertial *_msg, const gz::math::Inertiald &_data)
inline void 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());
Set(_msg, _data.MassMatrix());
Set(_msg->mutable_pose(), _data.Pose());

if (_data.FluidAddedMass().has_value())
{
Expand Down Expand Up @@ -108,16 +94,14 @@ inline void Converter<gz::msgs::Inertial, gz::math::Inertiald>::Set(
}
}

template<>
inline void Converter<gz::msgs::Inertial, gz::math::Inertiald>::Set(
gz::math::Inertiald *_data, const gz::msgs::Inertial &_msg)
inline void 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);
Set(&to_set, _msg);
_data->SetMassMatrix(to_set);

gz::math::Pose3d pose_to_set = _data->Pose();
Converter<gz::msgs::Pose, gz::math::Pose3d>::Set(&pose_to_set, _msg.pose());
Set(&pose_to_set, _msg.pose());
_data->SetPose(pose_to_set);

if (_msg.fluid_added_mass_size() == 21)
Expand Down Expand Up @@ -171,12 +155,16 @@ inline void Converter<gz::msgs::Inertial, gz::math::Inertiald>::Set(

inline gz::msgs::Inertial Convert(const gz::math::Inertiald &_data)
{
return Converter<gz::msgs::Inertial, gz::math::Inertiald>::Convert(_data);
gz::msgs::Inertial ret;
Set(&ret, _data);
return ret;
}

inline gz::math::Inertiald Convert(const gz::msgs::Inertial &_msg)
{
return Converter<gz::msgs::Inertial, gz::math::Inertiald>::Convert(_msg);
gz::math::Inertiald ret;
Set(&ret, _msg);
return ret;
}
} // namespce
} // namespace gz::msgs
Expand Down
26 changes: 11 additions & 15 deletions core/include/gz/msgs/convert/Plane.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#ifndef GZ_MSGS_CONVERT_PLANE_HH_
#define GZ_MSGS_CONVERT_PLANE_HH_

#include <gz/msgs/Converter.hh>
#include <gz/msgs/convert/Vector2.hh>
#include <gz/msgs/convert/Vector3.hh>

Expand All @@ -32,39 +31,36 @@ namespace gz::msgs {
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 Set(gz::msgs::PlaneGeom *_msg, const gz::math::Planed &_data)
{
Converter<gz::msgs::Vector3d, gz::math::Vector3d>::Set(
_msg->mutable_normal(), _data.Normal());
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 Set(gz::math::Planed *_data, const gz::msgs::PlaneGeom &_msg)
{
_data->Set(
Converter<gz::msgs::Vector3d, gz::math::Vector3d>::Convert(_msg.normal()),
Converter<gz::msgs::Vector2d, gz::math::Vector2d>::Convert(_msg.size()),
Convert(_msg.normal()),
Convert(_msg.size()),
_msg.d()
);
}

inline gz::msgs::PlaneGeom Convert(const gz::math::Planed &_data)
{
return Converter<gz::msgs::PlaneGeom, gz::math::Planed>::Convert(_data);
gz::msgs::PlaneGeom ret;
Set(&ret, _data);
return ret;
}

inline gz::math::Planed Convert(const gz::msgs::PlaneGeom &_msg)
{
return Converter<gz::msgs::PlaneGeom, gz::math::Planed>::Convert(_msg);
gz::math::Planed ret;
Set(&ret, _msg);
return ret;
}


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

Expand Down
Loading

0 comments on commit 5fc7a7e

Please sign in to comment.