Class UniversalAzimuthSubscriber
Defined in File message_filter.hpp
Inheritance Relationships
Base Types
public message_filters::SimpleFilter< compass_interfaces::msg::Azimuth >public message_filters::SubscriberBase
Class Documentation
-
class UniversalAzimuthSubscriber : public message_filters::SimpleFilter<compass_interfaces::msg::Azimuth>, public message_filters::SubscriberBase
message_filters subscriber that can subscribe to various topic types and convert them all to an Azimuth message.
Currently supported types are: compass_interfaces::msg::Azimuth, geometry_msgs::msg::PoseWithCovarianceStamped, geometry_msgs::msg::QuaternionStamped, sensor_msgs::msg::Imu.
Public Types
-
using NodeClockInterface = rclcpp::node_interfaces::NodeClockInterface
-
using NodeGraphInterface = rclcpp::node_interfaces::NodeGraphInterface
-
using NodeLoggingInterface = rclcpp::node_interfaces::NodeLoggingInterface
-
using NodeParametersInterface = rclcpp::node_interfaces::NodeParametersInterface
-
using NodeTopicsInterface = rclcpp::node_interfaces::NodeTopicsInterface
-
using RequiredInterfaces = rclcpp::node_interfaces::NodeInterfaces<NodeClockInterface, NodeGraphInterface, NodeLoggingInterface, NodeParametersInterface, NodeTopicsInterface>
-
typedef message_filters::MessageEvent<compass_interfaces::msg::Azimuth const> AzimuthEventType
-
typedef message_filters::MessageEvent<geometry_msgs::msg::PoseWithCovarianceStamped const> PoseEventType
-
typedef message_filters::MessageEvent<geometry_msgs::msg::QuaternionStamped const> QuatEventType
-
typedef message_filters::MessageEvent<sensor_msgs::msg::Imu const> ImuEventType
-
typedef message_filters::MessageEvent<rclcpp::SerializedMessage const> SerializedEventType
-
using Az = compass_interfaces::msg::Azimuth
-
using Unit = compass_interfaces::msg::Azimuth::_unit_type
-
using Orientation = compass_interfaces::msg::Azimuth::_orientation_type
-
using Reference = compass_interfaces::msg::Azimuth::_reference_type
-
using Variance = compass_interfaces::msg::Azimuth::_variance_type
Public Functions
-
UniversalAzimuthSubscriber(rclcpp::Node *node, const std::string &topic, rmw_qos_profile_t qos = rmw_qos_profile_default, rclcpp::SubscriptionOptions subscribeOptions = {})
Constructor.
- Parameters:
log – Logger.
nh – The ros::NodeHandle to use for subscribing.
topic – The topic to subscribe to.
queueSize – Queue size of the subscription.
-
inline UniversalAzimuthSubscriber(rclcpp::Node *node, const std::string &topic, rclcpp::QoS qos = {10}, rclcpp::SubscriptionOptions subscribeOptions = {})
-
~UniversalAzimuthSubscriber() override
-
void subscribe(rclcpp::Node *node, const std::string &topic, rmw_qos_profile_t qos, rclcpp::SubscriptionOptions subscribeOptions) override
-
inline void subscribe(NodePtr node, const std::string &topic, const rmw_qos_profile_t qos) override
-
inline void subscribe(rclcpp::Node *node, const std::string &topic, const rmw_qos_profile_t qos) override
-
void subscribe() override
Re-subscribe to a topic.
-
void unsubscribe() override
Unsubscribe from the topic.
-
void setInputDefaults(const std::optional<Orientation> &orientation, const std::optional<Reference> &reference, const std::optional<Variance> &variance)
Set defaults for inputs which do not support autodetection of various azimuth properties.
- Parameters:
orientation – [in] The default orientation used if it cannot be detected.
reference – [in] The reference used if it cannot be detected.
variance – [in] Default variance used for topics which cannot automatically discover it.
-
void configFromParams()
Configure the subscriber from ROS parameters.
Supported parameters:
~input_orientation(str, ‘enu’ or ‘ned’, default: unspecified): ENU or NED orientation to be used to interpret input messages (in case orientation cannot be derived either from message contents or topic name).~input_reference(str, ‘magnetic’, ‘geographic’ or ‘UTM’, default: no change): North reference to be used to interpret input messages (in case reference cannot be derived either from message contents or topic name).~input_variance(double, optional, rad^2): If specified, this variance will be used in the output messages if variance cannot be determined from the input messages (e.g. forQuaternionStamped).
-
std::string getTopic() const
Get the name of the subscribed topic.
- Returns:
The topic name.
-
inline const message_filters::Subscriber<compass_interfaces::msg::Azimuth> &getAzSubscriber() const
Returns the internal rclcpp::Subscription.
-
inline const message_filters::Subscriber<geometry_msgs::msg::PoseWithCovarianceStamped> &getPoseSubscriber() const
-
inline const message_filters::Subscriber<geometry_msgs::msg::QuaternionStamped> &getQuatSubscriber() const
-
inline const message_filters::Subscriber<sensor_msgs::msg::Imu> &getImuSubscriber() const
Protected Functions
-
void azCb(const AzimuthEventType &event)
-
void poseCb(const PoseEventType &event)
-
void quatCb(const QuatEventType &event)
-
void imuCb(const ImuEventType &event)
-
void serCb(const SerializedEventType &event)
Protected Attributes
-
message_filters::Subscriber<compass_interfaces::msg::Azimuth> azSub
-
message_filters::Subscriber<geometry_msgs::msg::PoseWithCovarianceStamped> poseSub
-
message_filters::Subscriber<geometry_msgs::msg::QuaternionStamped> quatSub
-
message_filters::Subscriber<sensor_msgs::msg::Imu> imuSub
-
message_filters::Subscriber<rclcpp::SerializedMessage> serSub
-
rclcpp::Node *node
-
CompassConverter converter
The azimuth message converter.
-
std::optional<Orientation> inputOrientation
Orientation of the input azimuth (in case it is a data type which does not tell orientation explicitly).
-
std::optional<Reference> inputReference
Reference of the input azimuth (in case it is a data type which does not tell reference explicitly).
-
std::optional<Variance> inputVariance
Variance of the input azimuth (in case it is a data type which does not tell reference explicitly).
-
std::string topic = {std::string()}
-
rclcpp::SubscriptionOptions options = {}
-
rmw_qos_profile_t qos = {rmw_qos_profile_default}
-
using NodeClockInterface = rclcpp::node_interfaces::NodeClockInterface