Class StateEstimatorBase

Inheritance Relationships

Derived Types

Class Documentation

class StateEstimatorBase

Subclassed by ground_truth::Plugin, mocap_pose::Plugin, raw_odometry::Plugin

Public Functions

inline StateEstimatorBase()
inline void setup(as2::Node *node, std::shared_ptr<as2::tf::TfHandler> tf_handler_, std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster, std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_tf_broadcaster)
virtual void on_setup() = 0
inline virtual bool get_earth_to_map_transform(geometry_msgs::msg::TransformStamped &transform)

Protected Functions

inline void check_standard_transform(const geometry_msgs::msg::TransformStamped &transform)
inline void publish_transform(const geometry_msgs::msg::TransformStamped &transform)
inline void publish_static_transform(const geometry_msgs::msg::TransformStamped &transform)
inline void publish_twist(const geometry_msgs::msg::TwistStamped &twist)
inline void publish_pose(const geometry_msgs::msg::PoseStamped &pose)
inline const std::string &get_earth_frame() const
inline const std::string &get_map_frame() const
inline const std::string &get_odom_frame() const
inline const std::string &get_base_frame() const
inline bool get_earth_to_map_transform(tf2::Transform &earth_to_map)

Protected Attributes

as2::Node *node_ptr_
std::shared_ptr<as2::tf::TfHandler> tf_handler_
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_
std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_tf_broadcaster_
rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr twist_pub_
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr pose_pub_
tf2::Transform odom_to_baselink
tf2::Transform earth_to_map
tf2::Transform earth_to_baselink
bool static_transforms_published_ = false
rclcpp::TimerBase::SharedPtr static_transforms_timer_