Skip to content

Commit

Permalink
FromLLArray - update after review
Browse files Browse the repository at this point in the history
  • Loading branch information
MarcinSlomiany committed May 8, 2022
1 parent cbcd769 commit dc74221
Show file tree
Hide file tree
Showing 3 changed files with 42 additions and 62 deletions.
7 changes: 7 additions & 0 deletions include/robot_localization/navsat_transform.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@
#include <Eigen/Dense>
#include <GeographicLib/Geocentric.hpp>
#include <GeographicLib/LocalCartesian.hpp>
#include <geographic_msgs/msg/geo_point.hpp>
#include <geometry_msgs/msg/point.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/imu.hpp>
Expand All @@ -51,6 +53,7 @@
#include <tf2_ros/transform_listener.h>

#include <memory>
#include <stdexcept>
#include <string>

namespace robot_localization
Expand Down Expand Up @@ -106,6 +109,10 @@ class NavSatTransform : public rclcpp::Node
const std::shared_ptr<robot_localization::srv::FromLLArray::Request> request,
std::shared_ptr<robot_localization::srv::FromLLArray::Response> response);

//! @brief Method for convert point from Lat Lon to the map coordinates system
//!
geometry_msgs::msg::Point fromLL(const geographic_msgs::msg::GeoPoint & geo_point);

/**
* @brief Given the pose of the navsat sensor in the Cartesian frame, removes the
* offset from the vehicle's centroid and returns the Cartesian-frame pose of said
Expand Down
95 changes: 34 additions & 61 deletions src/navsat_transform.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -408,9 +408,38 @@ bool NavSatTransform::fromLLCallback(
const std::shared_ptr<robot_localization::srv::FromLL::Request> request,
std::shared_ptr<robot_localization::srv::FromLL::Response> response)
{
double altitude = request->ll_point.altitude;
double longitude = request->ll_point.longitude;
double latitude = request->ll_point.latitude;
try {
response->map_point = fromLL(request->ll_point);
}
catch(const std::runtime_error& e) {
return false;
}

return true;
}

bool NavSatTransform::fromLLArrayCallback(
const std::shared_ptr<robot_localization::srv::FromLLArray::Request> request,
std::shared_ptr<robot_localization::srv::FromLLArray::Response> response)
{
for (auto it = request->ll_points.begin(); it != request->ll_points.end(); ++it) {
try {
response->map_points.push_back(fromLL(*it));
}
catch(const std::runtime_error& e) {
return false;
}
}

return true;
}

geometry_msgs::msg::Point NavSatTransform::fromLL(
const geographic_msgs::msg::GeoPoint& geo_point)
{
double altitude = geo_point.altitude;
double longitude = geo_point.longitude;
double latitude = geo_point.latitude;

tf2::Transform cartesian_pose;

Expand Down Expand Up @@ -438,67 +467,11 @@ bool NavSatTransform::fromLLCallback(

cartesian_pose.setOrigin(tf2::Vector3(cartesian_x, cartesian_y, altitude));

nav_msgs::msg::Odometry gps_odom;

if (!transform_good_) {
return false;
throw std::runtime_error("Invalid transform.");
}

response->map_point = cartesianToMap(cartesian_pose).pose.pose.position;

return true;
}

bool NavSatTransform::fromLLArrayCallback(
const std::shared_ptr<robot_localization::srv::FromLLArray::Request> request,
std::shared_ptr<robot_localization::srv::FromLLArray::Response> response)
{
double altitude, longitude, latitude;
double cartesian_x {};
double cartesian_y {};
double cartesian_z {};
tf2::Transform cartesian_pose;
std::string utm_zone_tmp;
for (auto it = request->ll_points.begin(); it != request->ll_points.end(); ++it) {
//
altitude = it->altitude;
longitude = it->longitude;
latitude = it->latitude;
cartesian_x = 0.0;
cartesian_y = 0.0;
cartesian_z = 0.0;
//
if (use_local_cartesian_) {
gps_local_cartesian_.Forward(
latitude,
longitude,
altitude,
cartesian_x,
cartesian_y,
cartesian_z);
} else {

navsat_conversions::LLtoUTM(
latitude,
longitude,
cartesian_y,
cartesian_x,
utm_zone_tmp);
}

cartesian_pose.setOrigin(tf2::Vector3(cartesian_x, cartesian_y, altitude));

// nav_msgs::msg::Odometry gps_odom; // it's unused?

if (!transform_good_) {
return false;
}

response->map_points.push_back(cartesianToMap(cartesian_pose).pose.pose.position);

}

return true;
return cartesianToMap(cartesian_pose).pose.pose.position;
}

nav_msgs::msg::Odometry NavSatTransform::cartesianToMap(
Expand Down
2 changes: 1 addition & 1 deletion srv/FromLLArray.srv
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
geographic_msgs/GeoPoint[] ll_points
---
geometry_msgs/Point[] map_points
geometry_msgs/Point[] map_points

0 comments on commit dc74221

Please sign in to comment.