diff --git a/rclpy/src/rclpy/action_client.hpp b/rclpy/src/rclpy/action_client.hpp
index 5e031e1f1..5dcf04b90 100644
--- a/rclpy/src/rclpy/action_client.hpp
+++ b/rclpy/src/rclpy/action_client.hpp
@@ -230,7 +230,7 @@ class ActionClient : public Destroyable, public std::enable_shared_from_this<Act
   Node node_;
   std::shared_ptr<rcl_action_client_t> rcl_action_client_;
 };
-/// Define a pybind11 wrapper for an rcl_time_point_t
+/// Define a pybind11 wrapper for an rclpy::ActionClient
 /**
  * \param[in] module a pybind11 module to add the definition to
  */
diff --git a/rclpy/src/rclpy/action_server.hpp b/rclpy/src/rclpy/action_server.hpp
index 39ac822fb..d812e8996 100644
--- a/rclpy/src/rclpy/action_server.hpp
+++ b/rclpy/src/rclpy/action_server.hpp
@@ -256,7 +256,7 @@ class ActionServer : public Destroyable, public std::enable_shared_from_this<Act
   Node node_;
   std::shared_ptr<rcl_action_server_t> rcl_action_server_;
 };
-/// Define a pybind11 wrapper for an rcl_time_point_t
+/// Define a pybind11 wrapper for an rclpy::ActionServer
 /**
  * \param[in] module a pybind11 module to add the definition to
  */
diff --git a/rclpy/src/rclpy/clock.hpp b/rclpy/src/rclpy/clock.hpp
index 5ef3c2a5a..53d0e0f4c 100644
--- a/rclpy/src/rclpy/clock.hpp
+++ b/rclpy/src/rclpy/clock.hpp
@@ -116,7 +116,7 @@ class Clock : public Destroyable, public std::enable_shared_from_this<Clock>
   std::shared_ptr<rcl_clock_t> rcl_clock_;
 };
 
-/// Define a pybind11 wrapper for an rclpy::Service
+/// Define a pybind11 wrapper for an rclpy::Clock
 void define_clock(py::object module);
 }  // namespace rclpy
 
diff --git a/rclpy/src/rclpy/context.hpp b/rclpy/src/rclpy/context.hpp
index c8be10eb7..cdeb14122 100644
--- a/rclpy/src/rclpy/context.hpp
+++ b/rclpy/src/rclpy/context.hpp
@@ -103,7 +103,7 @@ class Context : public Destroyable, public std::enable_shared_from_this<Context>
   std::shared_ptr<rcl_context_t> rcl_context_;
 };
 
-/// Define a pybind11 wrapper for an rclpy::Service
+/// Define a pybind11 wrapper for an rclpy::Context
 void define_context(py::object module);
 }  // namespace rclpy
 
diff --git a/rclpy/src/rclpy/guard_condition.hpp b/rclpy/src/rclpy/guard_condition.hpp
index 2866234a5..82828a79d 100644
--- a/rclpy/src/rclpy/guard_condition.hpp
+++ b/rclpy/src/rclpy/guard_condition.hpp
@@ -68,7 +68,7 @@ class GuardCondition : public Destroyable, public std::enable_shared_from_this<G
   }
 };
 
-/// Define a pybind11 wrapper for an rclpy::Service
+/// Define a pybind11 wrapper for an rclpy::GuardCondition
 void define_guard_condition(py::object module);
 }  // namespace rclpy
 
diff --git a/rclpy/src/rclpy/publisher.hpp b/rclpy/src/rclpy/publisher.hpp
index d87dae688..e49e632c3 100644
--- a/rclpy/src/rclpy/publisher.hpp
+++ b/rclpy/src/rclpy/publisher.hpp
@@ -131,7 +131,7 @@ class Publisher : public Destroyable, public std::enable_shared_from_this<Publis
   Node node_;
   std::shared_ptr<rcl_publisher_t> rcl_publisher_;
 };
-/// Define a pybind11 wrapper for an rclpy::Service
+/// Define a pybind11 wrapper for an rclpy::Publisher
 void define_publisher(py::object module);
 }  // namespace rclpy
 
diff --git a/rclpy/src/rclpy/subscription.hpp b/rclpy/src/rclpy/subscription.hpp
index 5737d64eb..f46401ea2 100644
--- a/rclpy/src/rclpy/subscription.hpp
+++ b/rclpy/src/rclpy/subscription.hpp
@@ -109,7 +109,7 @@ class Subscription : public Destroyable, public std::enable_shared_from_this<Sub
   Node node_;
   std::shared_ptr<rcl_subscription_t> rcl_subscription_;
 };
-/// Define a pybind11 wrapper for an rclpy::Service
+/// Define a pybind11 wrapper for an rclpy::Subscription
 void define_subscription(py::object module);
 }  // namespace rclpy
 
diff --git a/rclpy/src/rclpy/wait_set.hpp b/rclpy/src/rclpy/wait_set.hpp
index 3c1e00d94..24970080a 100644
--- a/rclpy/src/rclpy/wait_set.hpp
+++ b/rclpy/src/rclpy/wait_set.hpp
@@ -177,7 +177,7 @@ class WaitSet : public Destroyable, public std::enable_shared_from_this<WaitSet>
   std::shared_ptr<rcl_wait_set_t> rcl_wait_set_;
 };
 
-/// Define a pybind11 wrapper for an rclpy::Service
+/// Define a pybind11 wrapper for an rclpy::WaitSet
 void define_waitset(py::object module);
 }  // namespace rclpy