-
Notifications
You must be signed in to change notification settings - Fork 932
Added FromLLArray service #912
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from all commits
f164131
606d2c1
a171cd4
a0dc785
d44fc22
17eb055
2c7cd75
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -150,6 +150,8 @@ NavSatTransform::NavSatTransform(const rclcpp::NodeOptions & options) | |
"toLL", std::bind(&NavSatTransform::toLLCallback, this, _1, _2)); | ||
from_ll_srv_ = this->create_service<robot_localization::srv::FromLL>( | ||
"fromLL", std::bind(&NavSatTransform::fromLLCallback, this, _1, _2)); | ||
from_ll_array_srv_ = this->create_service<robot_localization::srv::FromLLArray>( | ||
"fromLLArray", std::bind(&NavSatTransform::fromLLArrayCallback, this, _1, _2)); | ||
|
||
set_utm_zone_srv_ = this->create_service<robot_localization::srv::SetUTMZone>( | ||
"setUTMZone", std::bind(&NavSatTransform::setUTMZoneCallback, this, _1, _2)); | ||
|
@@ -437,9 +439,40 @@ 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) | ||
{ | ||
decltype(response->map_points) converted_points; | ||
converted_points.reserve(request->ll_points.size()); | ||
|
||
try { | ||
std::transform(request->ll_points.begin(), request->ll_points.end(), | ||
std::back_inserter(converted_points), | ||
[this] (const auto& point) { return fromLL(point); }); | ||
} catch(const std::runtime_error & e) { | ||
return false; | ||
} | ||
|
||
response->map_points = std::move(converted_points); | ||
return true; | ||
} | ||
|
||
geometry_msgs::msg::Point NavSatTransform::fromLL( | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This throws an exception now. I just want to make sure that we're catching it everywhere it's called. I haven't looked through the code to remind myself. :) There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. its called from:
each of which does have it wrapped in a try catch |
||
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; | ||
|
||
|
@@ -466,21 +499,17 @@ bool NavSatTransform::fromLLCallback( | |
zone_tmp, northp_tmp, cartesian_x, cartesian_y, utm_zone_); | ||
} catch (GeographicLib::GeographicErr const & e) { | ||
RCLCPP_ERROR_STREAM(this->get_logger(), e.what()); | ||
return false; | ||
throw; | ||
} | ||
} | ||
|
||
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; | ||
return cartesianToMap(cartesian_pose).pose.pose.position; | ||
} | ||
|
||
bool NavSatTransform::setUTMZoneCallback( | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,3 @@ | ||
geographic_msgs/GeoPoint[] ll_points | ||
--- | ||
geometry_msgs/Point[] map_points |
Uh oh!
There was an error while loading. Please reload this page.