diff --git a/interbotix_ros_slate/interbotix_slate_driver/include/interbotix_slate_driver/slate_base.hpp b/interbotix_ros_slate/interbotix_slate_driver/include/interbotix_slate_driver/slate_base.hpp index 02e6f1a..8cd3353 100644 --- a/interbotix_ros_slate/interbotix_slate_driver/include/interbotix_slate_driver/slate_base.hpp +++ b/interbotix_ros_slate/interbotix_slate_driver/include/interbotix_slate_driver/slate_base.hpp @@ -103,7 +103,7 @@ class SlateBase : public rclcpp::Node rclcpp::Service::SharedPtr srv_motor_torque_status_; // Set charge enable service server - rclcpp::Service::SharedPtr srv_enable_charing_; + rclcpp::Service::SharedPtr srv_enable_charging_; // Set light state service server rclcpp::Service::SharedPtr srv_set_light_state_; @@ -205,13 +205,13 @@ class SlateBase : public rclcpp::Node const std::shared_ptr res); /** - * @brief Process incoming enable charing service request + * @brief Process incoming enable charging service request * @param request_header Incoming RMW request identifier - * @param req Service request containing desired charing enable status + * @param req Service request containing desired charging enable status * @param res[out] Service response containing a success indication and a message * @return true if service succeeded, false otherwise */ - bool enable_charing_callback( + bool enable_charging_callback( const std::shared_ptr request_header, const std::shared_ptr req, const std::shared_ptr res); diff --git a/interbotix_ros_slate/interbotix_slate_driver/src/slate_base.cpp b/interbotix_ros_slate/interbotix_slate_driver/src/slate_base.cpp index ae33edf..90da2f2 100644 --- a/interbotix_ros_slate/interbotix_slate_driver/src/slate_base.cpp +++ b/interbotix_ros_slate/interbotix_slate_driver/src/slate_base.cpp @@ -68,9 +68,9 @@ SlateBase::SlateBase(const rclcpp::NodeOptions & options) "set_motor_torque_status", std::bind(&SlateBase::motor_torque_status_callback, this, _1, _2, _3)); - srv_enable_charing_ = create_service( + srv_enable_charging_ = create_service( "enable_charging", - std::bind(&SlateBase::enable_charing_callback, this, _1, _2, _3)); + std::bind(&SlateBase::enable_charging_callback, this, _1, _2, _3)); srv_set_light_state_ = create_service( "set_light_state", @@ -227,7 +227,7 @@ bool SlateBase::motor_torque_status_callback( return res->success; } -bool SlateBase::enable_charing_callback( +bool SlateBase::enable_charging_callback( const std::shared_ptr/*request_header*/, const std::shared_ptr req, const std::shared_ptr res)