Skip to content

Commit 7fc5805

Browse files
authored
Merge pull request #320 from gazebosim/arjo/feat/environment_data_messages
Adds a message that allows loading environments via a topic
2 parents c7e0323 + 97531a0 commit 7fc5805

File tree

5 files changed

+184
-0
lines changed

5 files changed

+184
-0
lines changed

include/gz/msgs/Utility.hh

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -94,6 +94,14 @@ namespace gz
9494
math::SphericalCoordinates Convert(
9595
const msgs::SphericalCoordinates &_coord);
9696

97+
/// \brief Convert a msgs::SphericalCoordinatesType to an
98+
/// gz::math::SphericalCoordinates::CoordinateTpye
99+
/// \param[in] _sc The spherical coordinate type to convert
100+
/// \return A gz::math::SphericalCoordinatesType object
101+
GZ_MSGS_VISIBLE
102+
math::SphericalCoordinates::CoordinateType Convert(
103+
const msgs::SphericalCoordinatesType &_sc);
104+
97105
/// \brief Convert a msgs::AxisAlignedBox to an
98106
/// gz::math::AxisAlignedBox
99107
/// \param[in] _b The axis aligned box to convert
@@ -212,6 +220,14 @@ namespace gz
212220
msgs::SphericalCoordinates Convert(
213221
const math::SphericalCoordinates &_coord);
214222

223+
/// \brief Convert a gz::math::SphericalCoordinates::CoordinateType
224+
/// to a msgs::SphericalCoordinatesType
225+
/// \param[in] _coord The spherical coordinates type to convert
226+
/// \return A gz::msgs::SphericalCoordinatesType object
227+
GZ_MSGS_VISIBLE
228+
msgs::SphericalCoordinatesType ConvertCoord(
229+
const math::SphericalCoordinates::CoordinateType &_coord);
230+
215231
/// \brief Convert a gz::math::Planed to a msgs::PlaneGeom
216232
/// \param[in] _p The plane to convert
217233
/// \return A msgs::PlaneGeom object
Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
/*
2+
* Copyright (C) 2023 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*
16+
*/
17+
18+
syntax = "proto3";
19+
package gz.msgs;
20+
option java_package = "com.gz.msgs";
21+
option java_outer_classname = "DataLoadPathOptions";
22+
23+
import "gz/msgs/spherical_coordinates.proto";
24+
25+
/// \brief Used for specifying how to load environmental data
26+
message DataLoadPathOptions
27+
{
28+
/// \brief Units used by spherical coordinates
29+
enum DataAngularUnits
30+
{
31+
RADIANS = 0;
32+
DEGREES = 1;
33+
}
34+
35+
/// \brief File path to load
36+
string path = 1;
37+
38+
/// \brief Name of time axis
39+
string time = 2;
40+
41+
/// \brief Is the data static in time
42+
bool static_time = 3;
43+
44+
/// \brief Name of x axis
45+
string x = 4;
46+
47+
/// \brief Name of y axis
48+
string y = 5;
49+
50+
/// \brief Name of z axis
51+
string z = 6;
52+
53+
/// Units
54+
DataAngularUnits units = 7;
55+
56+
/// Spherical Coodinate type
57+
gz.msgs.SphericalCoordinatesType coordinate_type = 8;
58+
}

proto/gz/msgs/spherical_coordinates.proto

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,26 @@ option java_outer_classname = "SphericalCoordinatesProtos";
2727
import "gz/msgs/entity.proto";
2828
import "gz/msgs/header.proto";
2929

30+
enum SphericalCoordinatesType
31+
{
32+
/// \brief Latitude, Longitude and Altitude by SurfaceType
33+
SPHERICAL = 0;
34+
35+
/// \brief Earth centered, earth fixed Cartesian
36+
ECEF = 1;
37+
38+
/// \brief Local tangent plane (East, North, Up)
39+
GLOBAL = 2;
40+
41+
/// \brief Heading-adjusted tangent plane (X, Y, Z)
42+
/// This has kept a bug for backwards compatibility, use
43+
/// LOCAL2 for the correct behaviour.
44+
LOCAL = 3;
45+
46+
/// \brief Heading-adjusted tangent plane (X, Y, Z)
47+
LOCAL2 = 4;
48+
}
49+
3050
message SphericalCoordinates
3151
{
3252
/// \brief Planetary surface models.

src/Utility.cc

Lines changed: 50 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -176,6 +176,28 @@ namespace gz
176176
return out;
177177
}
178178

179+
/////////////////////////////////////////////
180+
math::SphericalCoordinates::CoordinateType Convert(
181+
const msgs::SphericalCoordinatesType &_sc)
182+
{
183+
switch (_sc)
184+
{
185+
case msgs::SphericalCoordinatesType::ECEF:
186+
return math::SphericalCoordinates::CoordinateType::ECEF;
187+
case msgs::SphericalCoordinatesType::GLOBAL:
188+
return math::SphericalCoordinates::CoordinateType::GLOBAL;
189+
case msgs::SphericalCoordinatesType::SPHERICAL:
190+
return math::SphericalCoordinates::CoordinateType::SPHERICAL;
191+
case msgs::SphericalCoordinatesType::LOCAL:
192+
return math::SphericalCoordinates::CoordinateType::LOCAL;
193+
case msgs::SphericalCoordinatesType::LOCAL2:
194+
return math::SphericalCoordinates::CoordinateType::LOCAL2;
195+
default:
196+
std::cerr << "Invalid coordinate type passed" << std::endl;
197+
}
198+
return math::SphericalCoordinates::CoordinateType::LOCAL2;
199+
}
200+
179201
/////////////////////////////////////////////
180202
math::AxisAlignedBox Convert(const msgs::AxisAlignedBox &_b)
181203
{
@@ -342,6 +364,34 @@ namespace gz
342364
return result;
343365
}
344366

367+
/////////////////////////////////////////////
368+
msgs::SphericalCoordinatesType ConvertCoord(
369+
const math::SphericalCoordinates::CoordinateType &_sc)
370+
{
371+
auto result = msgs::SphericalCoordinatesType::LOCAL2;
372+
switch (_sc)
373+
{
374+
case math::SphericalCoordinates::CoordinateType::ECEF:
375+
result = msgs::SphericalCoordinatesType::ECEF;
376+
break;
377+
case math::SphericalCoordinates::CoordinateType::GLOBAL:
378+
result = msgs::SphericalCoordinatesType::GLOBAL;
379+
break;
380+
case math::SphericalCoordinates::CoordinateType::SPHERICAL:
381+
result = msgs::SphericalCoordinatesType::SPHERICAL;
382+
break;
383+
case math::SphericalCoordinates::CoordinateType::LOCAL:
384+
result = msgs::SphericalCoordinatesType::LOCAL;
385+
break;
386+
case math::SphericalCoordinates::CoordinateType::LOCAL2:
387+
result = msgs::SphericalCoordinatesType::LOCAL2;
388+
break;
389+
default:
390+
std::cerr << "Invalid coordinate type passed" << std::endl;
391+
}
392+
return result;
393+
}
394+
345395
/////////////////////////////////////////////
346396
msgs::PlaneGeom Convert(const gz::math::Planed &_p)
347397
{

src/Utility_TEST.cc

Lines changed: 40 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -398,6 +398,46 @@ TEST(MsgsTest, ConvertMathSphericalCoordinatesToMsgs)
398398
EXPECT_DOUBLE_EQ(10000, mathCustom.SurfaceAxisPolar());
399399
}
400400

401+
/////////////////////////////////////////////////
402+
TEST(MsgsTest, ConvertMsgsSphericalCoordinatesTypeToMath)
403+
{
404+
EXPECT_EQ(Convert(msgs::SphericalCoordinatesType::ECEF),
405+
math::SphericalCoordinates::CoordinateType::ECEF);
406+
EXPECT_EQ(Convert(msgs::SphericalCoordinatesType::GLOBAL),
407+
math::SphericalCoordinates::CoordinateType::GLOBAL);
408+
EXPECT_EQ(Convert(msgs::SphericalCoordinatesType::SPHERICAL),
409+
math::SphericalCoordinates::CoordinateType::SPHERICAL);
410+
EXPECT_EQ(Convert(msgs::SphericalCoordinatesType::LOCAL),
411+
math::SphericalCoordinates::CoordinateType::LOCAL);
412+
EXPECT_EQ(Convert(msgs::SphericalCoordinatesType::LOCAL2),
413+
math::SphericalCoordinates::CoordinateType::LOCAL2);
414+
EXPECT_EQ(Convert((msgs::SphericalCoordinatesType)500000),
415+
math::SphericalCoordinates::CoordinateType::LOCAL2);
416+
}
417+
418+
/////////////////////////////////////////////////
419+
TEST(MsgsTest, ConvertMathSphericalCoordinatedTypeToMsg)
420+
{
421+
EXPECT_EQ(msgs::ConvertCoord(
422+
math::SphericalCoordinates::CoordinateType::ECEF),
423+
msgs::SphericalCoordinatesType::ECEF);
424+
EXPECT_EQ(msgs::ConvertCoord(
425+
math::SphericalCoordinates::CoordinateType::GLOBAL),
426+
msgs::SphericalCoordinatesType::GLOBAL);
427+
EXPECT_EQ(msgs::ConvertCoord(
428+
math::SphericalCoordinates::CoordinateType::SPHERICAL),
429+
msgs::SphericalCoordinatesType::SPHERICAL);
430+
EXPECT_EQ(msgs::ConvertCoord(
431+
math::SphericalCoordinates::CoordinateType::LOCAL),
432+
msgs::SphericalCoordinatesType::LOCAL);
433+
EXPECT_EQ(msgs::ConvertCoord(
434+
math::SphericalCoordinates::CoordinateType::LOCAL2),
435+
msgs::SphericalCoordinatesType::LOCAL2);
436+
EXPECT_EQ(msgs::ConvertCoord(
437+
(math::SphericalCoordinates::CoordinateType)500000),
438+
msgs::SphericalCoordinatesType::LOCAL2);
439+
}
440+
401441
/////////////////////////////////////////////////
402442
TEST(UtilityTest, ConvertStringMsg)
403443
{

0 commit comments

Comments
 (0)