Start Recording
Start recording mission data.
-
Service Name: log_manager/start_recording
-
Service Type: std_srvs/srv/Trigger
- Python
- C++
from clearpath_config.common.utils.yaml import read_yaml
import rclpy
from rclpy.node import Node
from std_srvs.srv import Trigger
ROBOT_CONFIG_PATH = '/etc/clearpath/robot.yaml'
LOGGING_NAME = 'StartLogger'
class Logger(Node):
def __init__(self, namespace: str):
super().__init__('start_logger_client')
self._start_logger_client = self.create_client(Trigger, f'/{namespace}/log_manager/start_recording')
while not self._start_logger_client.wait_for_service(timeout_sec=2.0):
self.get_logger().info(f'[{LOGGING_NAME}] /{namespace}/log_manager/start_recording service not available, waiting again...')
def start(self):
req = Trigger.Request()
self.future = self._start_logger_client.call_async(req)
self.future.add_done_callback(self.start_logger_srv_response_cb)
def start_logger_srv_response_cb(self, future):
try:
response = future.result()
if response.success:
self.get_logger().info(f'[{LOGGING_NAME}] Logger started!')
else:
self.get_logger().error(f'[{LOGGING_NAME}] Failed to start logger')
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']
logger = Logger(namespace)
logger.start()
rclpy.spin(logger)
if __name__ == '__main__':
main()
#include "rclcpp/rclcpp.hpp"
#include "std_srvs/srv/trigger.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("start_logger_client");
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr client =
node->create_client<std_srvs::srv::Trigger>("/" + namespace_ + "/" + std::string("log_manager/start_recording"));
auto request = std::make_shared<std_srvs::srv::Trigger::Request>();
while (!client->wait_for_service(2s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(rclcpp::get_logger("start_logger_client"), "Interrupted while waiting for the service. Exiting.");
return 0;
}
RCLCPP_INFO(rclcpp::get_logger("start_logger_client"), "/%s/log_manager/start_recording 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("start_logger_client"), "Logger started!");
}
else
{
RCLCPP_ERROR(rclcpp::get_logger("start_logger_client"), "Failed to start logger!");
}
} else {
RCLCPP_ERROR(rclcpp::get_logger("start_logger_client"), "Failed to call service /%s/log_manager/start_recording", namespace_.c_str());
}
rclcpp::shutdown();
return 0;
}