Skip to content

Commit

Permalink
make cpplint happy too
Browse files Browse the repository at this point in the history
  • Loading branch information
VX792 committed Apr 22, 2023
1 parent a7588fa commit 636810a
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 2 deletions.
2 changes: 1 addition & 1 deletion hardware_interface/include/hardware_interface/sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ class Sensor final
return_type read(const rclcpp::Time & time, const rclcpp::Duration & period);

HARDWARE_INTERFACE_PUBLIC
return_type write(const rclcpp::Time &, const rclcpp::Duration &) { return return_type::OK; };
return_type write(const rclcpp::Time &, const rclcpp::Duration &) { return return_type::OK; }

private:
std::unique_ptr<SensorInterface> impl_;
Expand Down
3 changes: 2 additions & 1 deletion hardware_interface/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -668,7 +668,8 @@ class ResourceStorage
/// List of async components by type
std::unordered_map<std::string, AsyncComponentThread> async_component_threads_;

// Update rate of the controller manager, and the clock interface of its node - used by async components.
// Update rate of the controller manager, and the clock interface of its node
// Used by async components.
unsigned int cm_update_rate_;
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
};
Expand Down

0 comments on commit 636810a

Please sign in to comment.