Doc fixups (#546)

* add missing docs for number_of_threads parameter

* add missing docs for start_parameter_services parameter

* add missing docs for parameters, rename short variable name

* doc fixups
This commit is contained in:
William Woodall 2018-08-31 18:32:20 -07:00 committed by GitHub
parent a55e320e6e
commit 198c6daf49
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
4 changed files with 17 additions and 6 deletions

View file

@ -45,6 +45,8 @@ public:
* once.
*
* \param args common arguments for all executors
* \param number_of_threads number of threads to have in the thread pool,
* the default 0 will use the number of cpu cores found instead
* \param yield_before_execute if true std::this_thread::yield() is called
*/
RCLCPP_PUBLIC

View file

@ -91,6 +91,8 @@ public:
* \param[in] use_global_arguments False to prevent node using arguments passed to the process.
* \param[in] use_intra_process_comms True to use the optimized intra-process communication
* pipeline to pass messages between nodes in the same process using shared memory.
* \param[in] start_parameter_services True to setup ROS interfaces for accessing parameters
* in the node.
*/
RCLCPP_PUBLIC
Node(

View file

@ -59,6 +59,7 @@ public:
* \param[in] type_support_handle rosidl type support struct, for the Message type of the topic.
* \param[in] topic_name Name of the topic to subscribe to.
* \param[in] subscription_options options for the subscription.
* \param[in] is_serialized is true if the message will be delivered still serialized
*/
RCLCPP_PUBLIC
SubscriptionBase(
@ -161,6 +162,7 @@ public:
* The constructor for a subscription is almost never called directly. Instead, subscriptions
* should be instantiated through Node::create_subscription.
* \param[in] node_handle rcl representation of the node that owns this subscription.
* \param[in] type_support_handle rosidl type support struct, for the Message type of the topic.
* \param[in] topic_name Name of the topic to subscribe to.
* \param[in] subscription_options options for the subscription.
* \param[in] callback User defined callback to call when a message is received.
@ -168,7 +170,7 @@ public:
*/
Subscription(
std::shared_ptr<rcl_node_t> node_handle,
const rosidl_message_type_support_t & ts,
const rosidl_message_type_support_t & type_support_handle,
const std::string & topic_name,
const rcl_subscription_options_t & subscription_options,
AnySubscriptionCallback<CallbackMessageT, Alloc> callback,
@ -177,7 +179,7 @@ public:
Alloc>::create_default())
: SubscriptionBase(
node_handle,
ts,
type_support_handle,
topic_name,
subscription_options,
rclcpp::subscription_traits::is_serialized_subscription_argument<CallbackMessageT>::value),