@@ -21,33 +21,29 @@ namespace interface
21
21
namespace gnss
22
22
{
23
23
24
- MappingUtils::MappingUtils ()
25
- {
26
- }
24
+ MappingUtils::MappingUtils () {}
27
25
28
- MappingUtils::~MappingUtils ()
29
- {
30
- }
26
+ MappingUtils::~MappingUtils () {}
31
27
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 ¶ms, double &x_out, double &y_out, double &z_out) {
29
+ if (params.proj_str .size () < 8 ) return ;
37
30
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 );
40
33
41
- if (P == 0 ) return ;
34
+ if (P == nullptr ) {
35
+ proj_context_destroy (C);
36
+ return ;
37
+ }
42
38
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 ;
48
44
49
- proj_destroy (P);
50
- proj_context_destroy (C);
45
+ proj_destroy (P);
46
+ proj_context_destroy (C);
51
47
}
52
48
} // namespace gnss
53
49
} // namespace interface
@@ -57,9 +53,19 @@ void GnssInterface::GnssCallBack(const sensor_msgs::msg::NavSatFix::SharedPtr ms
57
53
geometry_msgs::msg::PoseStamped pose_;
58
54
geometry_msgs::msg::PoseWithCovarianceStamped pose_cov_;
59
55
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
+
63
69
pose_.header = msg->header ;
64
70
pose_.header .frame_id = " map" ;
65
71
pose_.pose .position .x = p.pos .x ;
0 commit comments