Skip to content

Commit 2ca6c7b

Browse files
committed
encapsulate some function
Signed-off-by: mraditya01 <mraditya01@yahoo.com>
1 parent 17e9b52 commit 2ca6c7b

File tree

3 files changed

+55
-38
lines changed

3 files changed

+55
-38
lines changed

simulator/CARLA_Autoware/carla_gnss_interface/include/carla_gnss_interface/carla_gnss_interface_node.hpp

+21-14
Original file line numberDiff line numberDiff line change
@@ -88,30 +88,37 @@ class GPSPoint
8888
class WayPoint
8989
{
9090
public:
91-
GPSPoint pos;
92-
WayPoint() {}
91+
GPSPoint pos;
92+
WayPoint() {}
93+
94+
WayPoint(const double & x, const double & y, const double & z, const double & a)
95+
{
96+
pos.x = x;
97+
pos.y = y;
98+
pos.z = z;
99+
pos.a = a;
100+
}
101+
};
93102

94-
WayPoint(const double & x, const double & y, const double & z, const double & a)
95-
{
96-
pos.x = x;
97-
pos.y = y;
98-
pos.z = z;
99-
pos.a = a;
100-
}
103+
struct MappingParameters {
104+
std::string proj_str;
105+
WayPoint org;
106+
double lat;
107+
double lon;
108+
double alt;
101109
};
102110

103111
class MappingUtils
104112
{
105113
public:
106-
MappingUtils();
107-
virtual ~MappingUtils();
114+
MappingUtils();
115+
virtual ~MappingUtils();
108116

109-
static void llaToxyz(
110-
const std::string & proj_str, const WayPoint & origin, const double & lat, const double & lon,
111-
const double & alt, double & x_out, double & y_out, double & z_out);
117+
static void llaToxyz(const MappingParameters &params, double &x_out, double &y_out, double &z_out);
112118
};
113119

114120
} // namespace gnss
115121
} // namespace interface
116122

123+
117124
#endif // CARLA_GNSS_INTERFACE__CARLA_GNSS_INTERFACE_NODE_HPP_

simulator/CARLA_Autoware/carla_gnss_interface/src/carla_gnss_interface/carla_gnss_interface_node.cpp

+30-24
Original file line numberDiff line numberDiff line change
@@ -21,33 +21,29 @@ namespace interface
2121
namespace gnss
2222
{
2323

24-
MappingUtils::MappingUtils()
25-
{
26-
}
24+
MappingUtils::MappingUtils() {}
2725

28-
MappingUtils::~MappingUtils()
29-
{
30-
}
26+
MappingUtils::~MappingUtils() {}
3127

32-
void MappingUtils::llaToxyz(
33-
const std::string & proj_str, const WayPoint & origin, const double & lat, const double & lon,
34-
const double & alt, double & x_out, double & y_out, double & z_out)
35-
{
36-
if (proj_str.size() < 8) return;
28+
void MappingUtils::llaToxyz(const MappingParameters &params, double &x_out, double &y_out, double &z_out) {
29+
if (params.proj_str.size() < 8) return;
3730

38-
PJ_CONTEXT * C = proj_context_create();
39-
PJ * P = proj_create_crs_to_crs(C, "EPSG:4326", proj_str.c_str(), NULL);
31+
PJ_CONTEXT *C = proj_context_create();
32+
PJ *P = proj_create_crs_to_crs(C, "EPSG:4326", params.proj_str.c_str(), NULL);
4033

41-
if (P == 0) return;
34+
if (P == nullptr) {
35+
proj_context_destroy(C);
36+
return;
37+
}
4238

43-
PJ_COORD gps_degrees = proj_coord(lat, lon, alt, 0);
44-
PJ_COORD xyz_out = proj_trans(P, PJ_FWD, gps_degrees);
45-
x_out = xyz_out.enu.e + origin.pos.x;
46-
y_out = xyz_out.enu.n + origin.pos.y;
47-
z_out = xyz_out.enu.u + origin.pos.z;
39+
PJ_COORD gps_degrees = proj_coord(params.lat, params.lon, params.alt, 0);
40+
PJ_COORD xyz_out = proj_trans(P, PJ_FWD, gps_degrees);
41+
x_out = xyz_out.enu.e + params.org.pos.x;
42+
y_out = xyz_out.enu.n + params.org.pos.y;
43+
z_out = xyz_out.enu.u + params.org.pos.z;
4844

49-
proj_destroy(P);
50-
proj_context_destroy(C);
45+
proj_destroy(P);
46+
proj_context_destroy(C);
5147
}
5248
} // namespace gnss
5349
} // namespace interface
@@ -57,9 +53,19 @@ void GnssInterface::GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr ms
5753
geometry_msgs::msg::PoseStamped pose_;
5854
geometry_msgs::msg::PoseWithCovarianceStamped pose_cov_;
5955
interface::gnss::WayPoint origin, p;
60-
interface::gnss::MappingUtils::llaToxyz(
61-
"+proj=tmerc +lat_0=0 +lon_0=0 +k=0.9999 +x_0=0 +y_0=0 +ellps=GRS80 +units=m +no_defs", origin,
62-
msg->latitude, msg->longitude, msg->altitude, p.pos.x, p.pos.y, p.pos.z);
56+
// Create an instance of MappingUtils
57+
interface::gnss::MappingUtils mappingUtils;
58+
59+
// Create MappingParameters struct to hold the parameters
60+
interface::gnss::MappingParameters params;
61+
params.proj_str = "+proj=tmerc +lat_0=0 +lon_0=0 +k=0.9999 +x_0=0 +y_0=0 +ellps=GRS80 +units=m +no_defs";
62+
params.lat = msg->latitude;
63+
params.lon = msg->longitude;
64+
params.alt = msg->altitude;
65+
66+
// Call llaToxyz function
67+
mappingUtils.llaToxyz(params, p.pos.x, p.pos.y, p.pos.z);
68+
6369
pose_.header = msg->header;
6470
pose_.header.frame_id = "map";
6571
pose_.pose.position.x = p.pos.x;

simulator/CARLA_Autoware/carla_pointcloud_interface/CMakeLists.txt

+4
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,8 @@
11
cmake_minimum_required(VERSION 3.5)
2+
3+
find_package(autoware_cmake REQUIRED)
4+
autoware_package()
5+
26
project(carla_pointcloud_interface)
37
if(NOT CMAKE_CXX_STANDARD)
48
set(CMAKE_CXX_STANDARD 14)

0 commit comments

Comments
 (0)