Add default value to options in LifecycleNode construnctor. Update API documentation. (#775)

Signed-off-by: Esteve Fernandez <esteve@apache.org>
This commit is contained in:
Esteve Fernandez 2019-07-02 15:51:47 +02:00 committed by ivanpauno
parent 61312b0576
commit 378657865e

View file

@ -115,14 +115,13 @@ public:
/** /**
* \param[in] node_name Name of the node. * \param[in] node_name Name of the node.
* \param[in] namespace_ Namespace of the node. * \param[in] namespace_ Namespace of the node.
* \param[in] context The context for the node (usually represents the state of a process).
* \param[in] options Additional options to control creation of the node. * \param[in] options Additional options to control creation of the node.
*/ */
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
LifecycleNode( LifecycleNode(
const std::string & node_name, const std::string & node_name,
const std::string & namespace_, const std::string & namespace_,
const rclcpp::NodeOptions & options); const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
RCLCPP_LIFECYCLE_PUBLIC RCLCPP_LIFECYCLE_PUBLIC
virtual ~LifecycleNode(); virtual ~LifecycleNode();