Class BaseAMCLNode
Defined in File ros2_common.hpp
Inheritance Relationships
Base Type
public rclcpp_lifecycle::LifecycleNode
Derived Types
public beluga_amcl::AmclNode
(Class AmclNode)public beluga_amcl::NdtAmclNode
(Class NdtAmclNode)public beluga_amcl::NdtAmclNode3D
(Class NdtAmclNode3D)
Class Documentation
-
class BaseAMCLNode : public rclcpp_lifecycle::LifecycleNode
Base AMCL lifecycle node, with some basic common functionalities, such as transform tree utilities, common publishers, subscribers, lifecycle related callbacks and configuration points, enabling extension by inheritance.
Subclassed by beluga_amcl::AmclNode, beluga_amcl::NdtAmclNode, beluga_amcl::NdtAmclNode3D
Public Functions
-
explicit BaseAMCLNode(const std::string &node_name = "amcl", const std::string &node_namespace = "", const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions{})
Constructor, following LifecycleNode signature.
-
~BaseAMCLNode() override
Destructor for the base AMCL node.
Protected Functions
-
CallbackReturn on_configure(const rclcpp_lifecycle::State&) override
Callback for lifecycle transitions from the UNCONFIGURED state to the INACTIVE state.
-
CallbackReturn on_activate(const rclcpp_lifecycle::State&) override
Callback for lifecycle transitions from the INACTIVE state to the ACTIVE state.
-
CallbackReturn on_deactivate(const rclcpp_lifecycle::State&) override
Callback for lifecycle transitions from the ACTIVE state to the INACTIVE state.
-
CallbackReturn on_cleanup(const rclcpp_lifecycle::State&) override
Callback for lifecycle transitions from the INACTIVE state to the UNCONFIGURED state.
-
CallbackReturn on_shutdown(const rclcpp_lifecycle::State&) override
Callback for lifecycle transitions from most states to the FINALIZED state.
-
auto get_execution_policy() const -> ExecutionPolicyVariant
Get execution policy from parameters.
-
void periodic_timer_callback()
Callback for the periodic particle updates.
-
void autostart_callback()
Callback for the autostart timer.
-
inline virtual void do_autostart_callback()
User provided extra steps for the autostart process.
-
inline virtual void do_configure(const rclcpp_lifecycle::State &state)
Extra steps for the on_configure callback. Defaults to no-op.
-
inline virtual void do_deactivate(const rclcpp_lifecycle::State &state)
Extra steps for the on_deactivate callback. Defaults to no-op.
-
inline virtual void do_shutdown(const rclcpp_lifecycle::State &state)
Extra steps for the on_shutdown callback. Defaults to no-op.
-
inline virtual void do_cleanup(const rclcpp_lifecycle::State &state)
Extra steps for the on_cleanup callback. Defaults to no-op.
-
inline virtual void do_activate(const rclcpp_lifecycle::State &state)
Extra steps for the on_activate callback. Defaults to no-op.
-
inline virtual void do_periodic_timer_callback()
Extra steps for the periodic updates timer callback events. Defaults to no-op.
Extra steps for (re)initialization messages.
Callback for (re)initialization messages.
Protected Attributes
-
rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseArray>::SharedPtr particle_cloud_pub_
Particle cloud publisher.
-
rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr particle_markers_pub_
Particle markers publisher.
-
rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr pose_pub_
Estimated pose publisher.
-
std::unique_ptr<bond::Bond> bond_
Node bond with the lifecycle manager.
-
rclcpp::TimerBase::SharedPtr timer_
Timer for periodic particle cloud updates.
-
std::unique_ptr<tf2_ros::Buffer> tf_buffer_
Transforms buffer.
-
std::unique_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_
Transforms broadcaster.
-
std::unique_ptr<tf2_ros::TransformListener> tf_listener_
Transforms listener.
-
rclcpp::TimerBase::SharedPtr autostart_timer_
Timer for node to configure and activate itself.
-
rclcpp::CallbackGroup::SharedPtr common_callback_group_
Common mutually exclusive callback group.
-
rclcpp::SubscriptionOptions common_subscription_options_
Common subscription options.
-
rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr initial_pose_sub_
Pose (re)initialization subscription.
-
explicit BaseAMCLNode(const std::string &node_name = "amcl", const std::string &node_namespace = "", const rclcpp::NodeOptions &node_options = rclcpp::NodeOptions{})