10#ifndef DVL_SETTING_HPP_
11#define DVL_SETTING_HPP_
13#include <driver_msgs/srv/command.hpp>
15#include <rclcpp/rclcpp.hpp>
36 rclcpp::Client<driver_msgs::srv::Command>::SharedPtr client_;
39 std::string config_file_path_;
42 std::vector<std::string> load_config_file(
const std::string & path);
45 std::string call_service(
const std::string & command);
48 bool execute_command(
const std::string & cmd);
49 std::string get_query_command(
const std::string & cmd);
50 std::string trim(
const std::string & str);
Definition: dvl_setting.hpp:23
bool configure()
Main routine to read config file and apply settings via Service.
Definition: dvl_setting.cpp:63
DVLSetting()
Definition: dvl_setting.cpp:32
~DVLSetting()
Definition: dvl_setting.cpp:61
Namespace for DVL driver components.