Set Datum
Set the datum. The datum is the reference coordinate of the navigations "map" frame. The XY position of the robot is relative to this location.
-
Service Name: localization/set_datum
-
Service Type: clearpath_localization_msgs/srv/SetDatum
- Python
- C++
import rclpy
from rclpy.node import Node
from clearpath_localization_msgs.srv import SetDatum
DATUM_LAT = 43.500049591064453
DATUM_LON = -80.546844482421875
class SetDatum(Node):
def __init__(self):
super().__init__('set_datum_client')
self._srv_client = self.create_client(SetDatum, 'localization/set_datum')
while not self._srv_client.wait_for_service(timeout_sec=1.0):
self.get_logger().info('service not available, waiting again...')
self.req = SetDatum.Request()
def send_request(self, lat, lon):
self.req.lat = lat
self.req.lon = lon
self.future = self._srv_client.call_async(self.req)
rclpy.spin_until_future_complete(self, self.future)
return self.future.result()
if __name__ == '__main__':
rclpy.init(args=args)
set_datum_client = SetDatum()
response = set_datum_client.send_request(DATUM_LAT, DATUM_LON)
if response.success:
set_datum_client.get_logger().info('Datum set succesfully: (%s, %s)' % (DATUM_LAT, DATUM_LON))
else:
set_datum_client.get_logger().error('Set datum failed!')
set_datum_client.destroy_node()
rclpy.shutdown()
#include "rclcpp/rclcpp.hpp"
#include "clearpath_localization_msgs/srv/set_datum.hpp"
#include <chrono>
#include <cstdlib>
#include <memory>
using namespace std::chrono_literals;
const double DATUM_LAT = 43.500049591064453;
const double DATUM_LON = -80.546844482421875;
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("set_datum_client");
rclcpp::Client<clearpath_localization_msgs::srv::SetDatum>::SharedPtr client =
node->create_client<clearpath_localization_msgs::srv::SetDatum>("localization/set_datum");
auto request = std::make_shared<clearpath_localization_msgs::srv::SetDatum::Request>();
request->lat = DATUM_LAT;
request->lon = DATUM_LON;
while (!client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Interrupted while waiting for the service. Exiting.");
return 0;
}
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "service not available, waiting again...");
}
auto result = client->async_send_request(request);
// Wait for the result.
if (rclcpp::spin_until_future_complete(node, result) ==
rclcpp::FutureReturnCode::SUCCESS)
{
if (result.get()->success)
{
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Datum set successfully: (%s, %s)", );
}
else
{
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Set datum failed!");
}
} else {
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service localization/set_datum");
}
rclcpp::shutdown();
return 0;
}