Class design#
We'll use the autoware_gnss_poser package as an example.
Namespaces#
namespace autoware::gnss_poser
{
...
} // namespace autoware::gnss_poser
- Everything should be under
autoware::gnss_posernamespace. - Closing braces must contain a comment with the namespace name. (Automated with
cpplint)
Classes#
Nodes#
gnss_poser_node.hpp#
class GNSSPoser : public rclcpp::Node
{
public:
explicit GNSSPoser(const rclcpp::NodeOptions & node_options);
...
}
gnss_poser_node.cpp#
GNSSPoser::GNSSPoser(const rclcpp::NodeOptions & node_options)
: Node("gnss_poser", node_options)
{
...
}
- The class name should be in
CamelCase. - Node classes should inherit from
rclcpp::Node. - The constructor must be marked be explicit.
- The constructor must take
rclcpp::NodeOptionsas an argument. - Default node name:
- should not have
autoware_prefix. - should NOT have
_nodesuffix.- Rationale: Node names are useful in the runtime. And output of
ros2 node listwill show only nodes anyway. Having_nodeis redundant.
- Rationale: Node names are useful in the runtime. And output of
- Example:
gnss_poser.
- should not have
Component registration#
...
} // namespace autoware::gnss_poser
#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::gnss_poser::GNSSPoser)
- The component should be registered at the end of the
gnss_poser_node.cppfile, outside the namespaces.
Libraries#
Warning
Under Construction