37
37
* @author Jaeyoung Lim <[email protected] >
38
38
*/
39
39
40
- #include < grid_map_geo/grid_map_geo.h >
41
- #include < grid_map_msgs/GridMap.h >
42
- #include < ros/ros.h >
40
+ #include < grid_map_geo/grid_map_geo.hpp >
41
+ #include < grid_map_msgs/msg/grid_map.hpp >
42
+ #include < rclcpp/rclcpp.hpp >
43
43
#include < grid_map_ros/GridMapRosConverter.hpp>
44
44
45
45
#include < gdal/ogr_spatialref.h>
46
+ #include < gdal/ogr_geometry.h>
46
47
47
48
constexpr int ESPG_WGS84 = 4326 ;
48
49
constexpr int ESPG_CH1903_LV03 = 21781 ;
@@ -67,7 +68,8 @@ void transformCoordinates(int src_coord, const double &x, const double &y, const
67
68
}
68
69
69
70
void LoadTerrainFromVrt (std::string path, const Eigen::Vector3d &query_position, const Eigen::Vector2d &offset,
70
- grid_map::GridMap &map, grid_map::GridMap &vrt_map_object) {
71
+ grid_map::GridMap &map, grid_map::GridMap &vrt_map_object,
72
+ rclcpp::Node::SharedPtr node_ptr) {
71
73
std::shared_ptr<GridMapGeo> vrt_map = std::make_shared<GridMapGeo>();
72
74
73
75
Eigen::Vector3d query_position_lv03 = query_position;
@@ -80,7 +82,7 @@ void LoadTerrainFromVrt(std::string path, const Eigen::Vector3d &query_position,
80
82
std::cout << " - map_center_wgs84:" << map_center_wgs84.transpose () << std::endl;
81
83
// / TODO: Discover extent from corners
82
84
Eigen::Vector2d extent_wgs84 (0.5 , 0.5 );
83
- vrt_map->initializeFromVrt (path, map_center_wgs84.head (2 ), extent_wgs84);
85
+ vrt_map->initializeFromVrt (path, map_center_wgs84.head (2 ), extent_wgs84, node_ptr );
84
86
std::cout << " - Success!" << std::endl;
85
87
86
88
// / TODO: Loaded VRT map
@@ -115,15 +117,16 @@ void LoadTerrainFromVrt(std::string path, const Eigen::Vector3d &query_position,
115
117
}
116
118
117
119
int main (int argc, char **argv) {
118
- ros::init (argc, argv, " terrain_loader" );
119
- ros::NodeHandle nh (" " );
120
- ros::NodeHandle nh_private (" ~" );
120
+ rclcpp::init (argc, argv);
121
+ // ros::init(argc, argv, "terrain_loader");
122
+ auto node = rclcpp::Node::make_shared (" terrain_loader" );
123
+ // ros::NodeHandle nh("");
124
+ // ros::NodeHandle nh_private("~");
121
125
122
- ros::Publisher map_pub = nh. advertise <grid_map_msgs::GridMap>(" grid_map" , 1 , true );
123
- ros::Publisher map_pub2 = nh. advertise <grid_map_msgs::GridMap>(" grid_map2" , 1 , true );
126
+ auto map_pub = node-> create_publisher <grid_map_msgs::msg:: GridMap>(" grid_map" , rclcpp::QoS ( 1 ). transient_local () );
127
+ auto map_pub2 = node-> create_publisher <grid_map_msgs::msg:: GridMap>(" grid_map2" , rclcpp::QoS ( 1 ). transient_local () );
124
128
125
- std::string path;
126
- nh_private.param <std::string>(" terrain_path" , path, " resources/cadastre.tif" );
129
+ auto const path = node->declare_parameter (" terrain_path" , " resources/cadastre.tif" );
127
130
128
131
Eigen::Vector3d test_position = Eigen::Vector3d (783199.15 , 187585.10 , 0.0 );
129
132
@@ -133,18 +136,22 @@ int main(int argc, char **argv) {
133
136
134
137
grid_map::GridMap map;
135
138
grid_map::GridMap vrt_map;
136
- LoadTerrainFromVrt (path, query_position, offset.head (2 ), map, vrt_map);
139
+ LoadTerrainFromVrt (path, query_position, offset.head (2 ), map, vrt_map, node );
137
140
std::cout << " i: " << i << " offset: " << offset.transpose () << std::endl;
138
141
139
- grid_map_msgs::GridMap msg;
140
- grid_map::GridMapRosConverter::toMessage (map, msg);
141
- map_pub.publish (msg);
142
+ // grid_map_msgs::msg::GridMap msg;
143
+ auto msg = grid_map::GridMapRosConverter::toMessage (map);
144
+ if (msg) {
145
+ map_pub->publish (std::move (msg));
146
+ }
142
147
143
- grid_map_msgs::GridMap msg2;
144
- grid_map::GridMapRosConverter::toMessage (vrt_map, msg2);
145
- map_pub2.publish (msg2);
148
+ auto msg2 = grid_map::GridMapRosConverter::toMessage (vrt_map);
149
+ if (msg2) {
150
+ map_pub2->publish (std::move (msg2));
151
+ }
146
152
}
147
153
148
- ros::spin ();
154
+ rclcpp::spin (node);
155
+ rclcpp::shutdown ();
149
156
return 0 ;
150
157
}
0 commit comments