Resume Autonomy
Resume autonomy from a previouly paused state.
-
Service Name: autonomy/resume
-
Service Type: std_srvs/srv/SetBool
- Python
- C++
from clearpath_config.common.utils.yaml import read_yaml
import rclpy
from rclpy.node import Node
from std_srvs.srv import SetBool
ROBOT_CONFIG_PATH = '/etc/clearpath/robot.yaml'
LOGGING_NAME = 'ResumeAutonomy'
class ResumeAutonomy(Node):
def __init__(self, namespace: str):
super().__init__('resume_autonomy_client')
self._autonomy_resume_client = self.create_client(SetBool, f'/{namespace}/autonomy/resume')
while not self._autonomy_resume_client.wait_for_service(timeout_sec=2.0):
self.get_logger().info(f'[{LOGGING_NAME}] /{namespace}/autonomy/resume service not available, waiting again...')
def resume(self):
req = SetBool.Request()
req.data = True
self.future = self._autonomy_resume_client.call_async(req)
self.future.add_done_callback(self.autonomy_resume_srv_response_cb)
def autonomy_resume_srv_response_cb(self, future):
try:
response = future.result()
if response.success:
self.get_logger().info(f'[{LOGGING_NAME}] Autonomy resumed!')
else:
self.get_logger().error(f'[{LOGGING_NAME}] Failed to resume autonomy')
except Exception as e:
self.get_logger().error(f'[{LOGGING_NAME}] Service call failed: {e}')
self.destroy_node()
rclpy.shutdown()
def main(args=None):
rclpy.init(args=args)
robot_config = read_yaml(ROBOT_CONFIG_PATH)
namespace = robot_config['system']['ros2']['namespace']
resume_autonomy_client = ResumeAutonomy(namespace)
resume_autonomy_client.resume()
rclpy.spin(resume_autonomy_client)
if __name__ == '__main__':
main()
#include "rclcpp/rclcpp.hpp"
#include "std_srvs/srv/set_bool.hpp"
#include <chrono>
#include <cstdlib>
#include <memory>
#include <yaml-cpp/yaml.h>
using namespace std::chrono_literals;
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
YAML::Node robot_config = YAML::LoadFile("/etc/clearpath/robot.yaml");
std::string namespace_ = robot_config["system"]["ros2"]["namespace"].as<std::string>();
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("resume_autonomy_client");
rclcpp::Client<std_srvs::srv::SetBool>::SharedPtr client =
node->create_client<std_srvs::srv::SetBool>("/" + namespace_ + "/" + std::string("autonomy/resume"));
auto request = std::make_shared<std_srvs::srv::SetBool::Request>();
request->data = true;
while (!client->wait_for_service(2s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(rclcpp::get_logger("resume_autonomy_client"), "Interrupted while waiting for the service. Exiting.");
return 0;
}
RCLCPP_INFO(rclcpp::get_logger("resume_autonomy_client"), "/%s/autonomy/resume service not available, waiting again...", namespace_.c_str());
}
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("resume_autonomy_client"), "Autonomy resumed!");
}
else
{
RCLCPP_ERROR(rclcpp::get_logger("resume_autonomy_client"), "Autonomy failed to resume!");
}
} else {
RCLCPP_ERROR(rclcpp::get_logger("resume_autonomy_client"), "Failed to call service /%s/autonomy/resume", namespace_.c_str());
}
rclcpp::shutdown();
return 0;
}