Skip to content

Commit b118c49

Browse files
authored
Merge branch 'main' into scene_shadow_caster_material_name
2 parents 0187394 + adf2644 commit b118c49

File tree

5 files changed

+139
-4
lines changed

5 files changed

+139
-4
lines changed

include/ignition/msgs/Utility.hh

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
#include <ignition/math/Inertial.hh>
2727
#include <ignition/math/Pose3.hh>
2828
#include <ignition/math/Plane.hh>
29+
#include <ignition/math/SphericalCoordinates.hh>
2930
#include <ignition/math/Vector3.hh>
3031

3132
#include "ignition/msgs/config.hh"
@@ -85,6 +86,14 @@ namespace ignition
8586
IGNITION_MSGS_VISIBLE
8687
math::Inertiald Convert(const msgs::Inertial &_i);
8788

89+
/// \brief Convert a msgs::SphericalCoordinates to an
90+
/// ignition::math::SphericalCoordinates
91+
/// \param[in] _coord The spherical coordinates to convert
92+
/// \return An ignition::math::SphericalCoordinates object
93+
IGNITION_MSGS_VISIBLE
94+
math::SphericalCoordinates Convert(
95+
const msgs::SphericalCoordinates &_coord);
96+
8897
/// \brief Convert a msgs::AxisAlignedBox to an
8998
/// ignition::math::AxisAlignedBox
9099
/// \param[in] _b The axis aligned box to convert
@@ -195,6 +204,14 @@ namespace ignition
195204
IGNITION_MSGS_VISIBLE
196205
msgs::Inertial Convert(const math::MassMatrix3d &_m);
197206

207+
/// \brief Convert an math::SphericalCoordinates to a
208+
/// msgs::SphericalCoordinates
209+
/// \param[in] _coord The SphericalCoordinates to convert
210+
/// \return A msgs::SphericalCoordinates object
211+
IGNITION_MSGS_VISIBLE
212+
msgs::SphericalCoordinates Convert(
213+
const math::SphericalCoordinates &_coord);
214+
198215
/// \brief Convert a ignition::math::Planed to a msgs::PlaneGeom
199216
/// \param[in] _p The plane to convert
200217
/// \return A msgs::PlaneGeom object
@@ -352,6 +369,14 @@ namespace ignition
352369
IGNITION_MSGS_VISIBLE
353370
void Set(msgs::Inertial *_i, const math::MassMatrix3d &_m);
354371

372+
/// \brief Set a msgs::SphericalCoordinates from a
373+
/// math::SphericalCoordinates
374+
/// \param[out] _sc A msgs::SphericalCoordinates pointer
375+
/// \param[in] _m An math::SphericalCoordinates reference
376+
IGNITION_MSGS_VISIBLE
377+
void Set(msgs::SphericalCoordinates *_sc,
378+
const math::SphericalCoordinates &_m);
379+
355380
/// \brief Set a msgs::Plane from an ignition::math::Planed
356381
/// \param[out] _p A msgs::Plane pointer
357382
/// \param[in] _v An ignition::math::Planed reference

proto/ignition/msgs/entity_factory.proto

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -30,10 +30,11 @@ option java_outer_classname = "EntityFactoryProtos";
3030
/// 3. From a message (model / light)
3131
/// 4. Cloning an existing entity (clone_name)
3232

33-
import "ignition/msgs/pose.proto";
33+
import "ignition/msgs/header.proto";
3434
import "ignition/msgs/light.proto";
3535
import "ignition/msgs/model.proto";
36-
import "ignition/msgs/header.proto";
36+
import "ignition/msgs/pose.proto";
37+
import "ignition/msgs/spherical_coordinates.proto";
3738

3839
message EntityFactory
3940
{
@@ -60,6 +61,7 @@ message EntityFactory
6061
}
6162

6263
/// \brief Pose where the entity will be spawned in the world.
64+
/// If set, `spherical_coordinates` will be ignored.
6365
Pose pose = 7;
6466

6567
/// \brief New name for the entity, overrides the name on the SDF.
@@ -72,4 +74,9 @@ message EntityFactory
7274
/// \brief The pose will be defined relative to this frame. If left empty,
7375
/// the "world" frame will be used.
7476
string relative_to = 10;
77+
78+
/// \brief Spherical coordinates where the entity will be spawned in the
79+
/// world.
80+
/// It's ignored if `pose` is set.
81+
SphericalCoordinates spherical_coordinates = 11;
7582
}

proto/ignition/msgs/spherical_coordinates.proto

Lines changed: 18 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,23 +22,39 @@ option java_outer_classname = "SphericalCoordinatesProtos";
2222

2323
/// \ingroup ignition.msgs
2424
/// \interface SphericalCoordinates
25-
/// \brief Spherical coordinates information
25+
/// \brief Spherical coordinates information
2626

27+
import "ignition/msgs/entity.proto";
2728
import "ignition/msgs/header.proto";
2829

2930
message SphericalCoordinates
3031
{
32+
/// \brief Planetary surface models.
3133
enum SurfaceModel
3234
{
35+
/// \brief World Geodetic System 1984
3336
EARTH_WGS84 = 0;
3437
}
3538

36-
/// \brief Optional header data
39+
/// \brief Optional header data.
3740
Header header = 1;
3841

42+
/// \brief Planetary surface model.
3943
SurfaceModel surface_model = 2;
44+
45+
/// \brief Latitude in degrees.
4046
double latitude_deg = 3;
47+
48+
/// \brief Longitude in degrees.
4149
double longitude_deg = 4;
50+
51+
/// \brief Elevation in meters.
4252
double elevation = 5;
53+
54+
/// \brief Heading in degrees.
4355
double heading_deg = 6;
56+
57+
/// \brief Entity that the coordinates apply to.
58+
/// If not set, defaults to the world origin.
59+
Entity entity = 7;
4460
}

src/Utility.cc

Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -120,6 +120,27 @@ namespace ignition
120120
pose);
121121
}
122122

123+
/////////////////////////////////////////////
124+
math::SphericalCoordinates Convert(const msgs::SphericalCoordinates &_sc)
125+
{
126+
math::SphericalCoordinates out;
127+
if (_sc.surface_model() == msgs::SphericalCoordinates::EARTH_WGS84)
128+
{
129+
out.SetSurface(math::SphericalCoordinates::EARTH_WGS84);
130+
}
131+
else
132+
{
133+
std::cerr << "Unrecognized spherical surface type ["
134+
<< _sc.surface_model()
135+
<< "]. Using default." << std::endl;
136+
}
137+
out.SetLatitudeReference(IGN_DTOR(_sc.latitude_deg()));
138+
out.SetLongitudeReference(IGN_DTOR(_sc.longitude_deg()));
139+
out.SetElevationReference(_sc.elevation());
140+
out.SetHeadingOffset(IGN_DTOR(_sc.heading_deg()));
141+
return out;
142+
}
143+
123144
/////////////////////////////////////////////
124145
math::AxisAlignedBox Convert(const msgs::AxisAlignedBox &_b)
125146
{
@@ -278,6 +299,14 @@ namespace ignition
278299
return result;
279300
}
280301

302+
/////////////////////////////////////////////
303+
msgs::SphericalCoordinates Convert(const math::SphericalCoordinates &_sc)
304+
{
305+
msgs::SphericalCoordinates result;
306+
msgs::Set(&result, _sc);
307+
return result;
308+
}
309+
281310
/////////////////////////////////////////////
282311
msgs::PlaneGeom Convert(const ignition::math::Planed &_p)
283312
{
@@ -433,6 +462,26 @@ namespace ignition
433462
msgs::Set(_i->mutable_pose(), _m.Pose());
434463
}
435464

465+
/////////////////////////////////////////////////
466+
void Set(msgs::SphericalCoordinates *_sc,
467+
const math::SphericalCoordinates &_m)
468+
{
469+
if (_m.Surface() == math::SphericalCoordinates::EARTH_WGS84)
470+
{
471+
_sc->set_surface_model(msgs::SphericalCoordinates::EARTH_WGS84);
472+
}
473+
else
474+
{
475+
std::cerr << "Unrecognized spherical surface type ["
476+
<< _m.Surface()
477+
<< "]. Not populating message field." << std::endl;
478+
}
479+
_sc->set_latitude_deg(_m.LatitudeReference().Degree());
480+
_sc->set_longitude_deg(_m.LongitudeReference().Degree());
481+
_sc->set_elevation(_m.ElevationReference());
482+
_sc->set_heading_deg(_m.HeadingOffset().Degree());
483+
}
484+
436485
/////////////////////////////////////////////////
437486
void Set(msgs::StringMsg *_p, const std::string &_v)
438487
{

src/Utility_TEST.cc

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -236,6 +236,29 @@ TEST(MsgsTest, ConvertMathMassMatrix3ToMsgs)
236236
EXPECT_EQ(ignition::math::Pose3d::Zero, msgs::Convert(msg.pose()));
237237
}
238238

239+
/////////////////////////////////////////////////
240+
TEST(MsgsTest, ConvertMathSphericalCoordinatesToMsgs)
241+
{
242+
auto msg = msgs::Convert(
243+
math::SphericalCoordinates(
244+
math::SphericalCoordinates::SurfaceType::EARTH_WGS84,
245+
IGN_DTOR(1.1), IGN_DTOR(2.2), 3.3, IGN_DTOR(0.4)));
246+
247+
EXPECT_EQ(msgs::SphericalCoordinates::EARTH_WGS84, msg.surface_model());
248+
EXPECT_DOUBLE_EQ(1.1, msg.latitude_deg());
249+
EXPECT_DOUBLE_EQ(2.2, msg.longitude_deg());
250+
EXPECT_DOUBLE_EQ(3.3, msg.elevation());
251+
EXPECT_DOUBLE_EQ(0.4, msg.heading_deg());
252+
253+
auto math = msgs::Convert(msg);
254+
255+
EXPECT_EQ(math::SphericalCoordinates::EARTH_WGS84, math.Surface());
256+
EXPECT_DOUBLE_EQ(1.1, math.LatitudeReference().Degree());
257+
EXPECT_DOUBLE_EQ(2.2, math.LongitudeReference().Degree());
258+
EXPECT_DOUBLE_EQ(3.3, math.ElevationReference());
259+
EXPECT_DOUBLE_EQ(0.4, math.HeadingOffset().Degree());
260+
}
261+
239262
/////////////////////////////////////////////////
240263
TEST(UtilityTest, ConvertStringMsg)
241264
{
@@ -451,6 +474,21 @@ TEST(MsgsTest, SetMassMatrix3)
451474
EXPECT_EQ(ignition::math::Pose3d::Zero, msgs::Convert(msg.pose()));
452475
}
453476

477+
/////////////////////////////////////////////////
478+
TEST(MsgsTest, SetSphericalCoordinates)
479+
{
480+
msgs::SphericalCoordinates msg;
481+
msgs::Set(&msg, math::SphericalCoordinates(
482+
math::SphericalCoordinates::SurfaceType::EARTH_WGS84,
483+
IGN_DTOR(1.1), IGN_DTOR(2.2), 3.3, IGN_DTOR(0.4)));
484+
485+
EXPECT_EQ(msgs::SphericalCoordinates::EARTH_WGS84, msg.surface_model());
486+
EXPECT_DOUBLE_EQ(1.1, msg.latitude_deg());
487+
EXPECT_DOUBLE_EQ(2.2, msg.longitude_deg());
488+
EXPECT_DOUBLE_EQ(3.3, msg.elevation());
489+
EXPECT_DOUBLE_EQ(0.4, msg.heading_deg());
490+
}
491+
454492
/////////////////////////////////////////////////
455493
TEST(MsgsTest, SetStringMsg)
456494
{

0 commit comments

Comments
 (0)