Skip to content

Commit

Permalink
fix spelling: charing -> charging (#51)
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson authored and lukeschmitt-tr committed Jul 26, 2024
1 parent a58ef0f commit 6e942ae
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ class SlateBase : public rclcpp::Node
rclcpp::Service<SetBool>::SharedPtr srv_motor_torque_status_;

// Set charge enable service server
rclcpp::Service<SetBool>::SharedPtr srv_enable_charing_;
rclcpp::Service<SetBool>::SharedPtr srv_enable_charging_;

// Set light state service server
rclcpp::Service<SetLightState>::SharedPtr srv_set_light_state_;
Expand Down Expand Up @@ -205,13 +205,13 @@ class SlateBase : public rclcpp::Node
const std::shared_ptr<SetBool::Response> 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<rmw_request_id_t> request_header,
const std::shared_ptr<SetBool::Request> req,
const std::shared_ptr<SetBool::Response> res);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<SetBool>(
srv_enable_charging_ = create_service<SetBool>(
"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<SetLightState>(
"set_light_state",
Expand Down Expand Up @@ -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<rmw_request_id_t>/*request_header*/,
const std::shared_ptr<SetBool::Request> req,
const std::shared_ptr<SetBool::Response> res)
Expand Down

0 comments on commit 6e942ae

Please sign in to comment.