diff --git a/autonav_ws/src/scr/include/scr/states.hpp b/autonav_ws/src/scr/include/scr/states.hpp index 49ab3815..269d8149 100644 --- a/autonav_ws/src/scr/include/scr/states.hpp +++ b/autonav_ws/src/scr/include/scr/states.hpp @@ -14,7 +14,7 @@ namespace SCR ERRORED = 5 }; - std::string getAsString(DeviceState state) + std::string toString(DeviceState state) { switch (state) { @@ -42,7 +42,7 @@ namespace SCR SHUTDOWN = 3 }; - std::string getAsString(SystemState state) + std::string toString(SystemState state) { switch (state) { @@ -65,7 +65,7 @@ namespace SCR PRACTICE = 2, }; - std::string getAsString(SystemMode state) + std::string toString(SystemMode state) { switch (state) { diff --git a/autonav_ws/src/scr/src/node.cpp b/autonav_ws/src/scr/src/node.cpp index 0d62cf79..a0694579 100644 --- a/autonav_ws/src/scr/src/node.cpp +++ b/autonav_ws/src/scr/src/node.cpp @@ -50,8 +50,8 @@ namespace SCR SCR::SystemMode newMode = static_cast(msg.mode); SCR::SystemMode oldMode = static_cast(oldState.mode); - RCLCPP_WARN(this->get_logger(), "SYSTEM STATE CHANGE: %s -> %s", SCR::getAsString(oldStateEnum).c_str(), SCR::getAsString(newStateEnum).c_str()); - RCLCPP_WARN(this->get_logger(), "SYSTEM MODE CHANGE: %s -> %s", SCR::getAsString(oldMode).c_str(), SCR::getAsString(newMode).c_str()); + RCLCPP_WARN(this->get_logger(), "SYSTEM STATE CHANGE: %s -> %s", SCR::toString(oldStateEnum).c_str(), SCR::toString(newStateEnum).c_str()); + RCLCPP_WARN(this->get_logger(), "SYSTEM MODE CHANGE: %s -> %s", SCR::toString(oldMode).c_str(), SCR::toString(newMode).c_str()); RCLCPP_WARN(this->get_logger(), "MOBILITY CHANGE: %d -> %d", oldState.mobility, msg.mobility); system_state_transition(oldState, msg); @@ -76,7 +76,7 @@ namespace SCR } device_state = static_cast(msg.state); - RCLCPP_INFO(this->get_logger(), "Received Topic: Device state changed to %s", SCR::getAsString(device_state).c_str()); + RCLCPP_INFO(this->get_logger(), "Received Topic: Device state changed to %s", SCR::toString(device_state).c_str()); if (device_state == SCR::DeviceState::BOOTING) { @@ -166,7 +166,7 @@ namespace SCR auto result = result_future.get(); if (!result) { - RCLCPP_ERROR(this->get_logger(), "Failed to set device state to: %s", SCR::getAsString(state).c_str()); + RCLCPP_ERROR(this->get_logger(), "Failed to set device state to: %s", SCR::toString(state).c_str()); } } diff --git a/autonav_ws/src/scr_controller/src/core.cpp b/autonav_ws/src/scr_controller/src/core.cpp index 2213c03c..0c39c823 100644 --- a/autonav_ws/src/scr_controller/src/core.cpp +++ b/autonav_ws/src/scr_controller/src/core.cpp @@ -95,7 +95,7 @@ class CoreNode : public rclcpp::Node } // Update the device state - RCLCPP_INFO(this->get_logger(), "Device %s state changed to %s", request->device.c_str(), SCR::getAsString((SCR::DeviceState)request->state).c_str()); + RCLCPP_INFO(this->get_logger(), "Device %s state changed to %s", request->device.c_str(), SCR::toString((SCR::DeviceState)request->state).c_str()); if (device_states.find(request->device) == device_states.end()) { // This is the first time we've seen this device, so we need to publish the system state, device state, and all known configs