compass_conversions::UniversalAzimuthSubscriber Class Reference

message_filters subscriber that can subscribe to various topic types and convert them all to an Azimuth message. More...

#include <message_filter.h>

Inheritance diagram for compass_conversions::UniversalAzimuthSubscriber:

Public Types

typedef ros::MessageEvent< topic_tools::ShapeShifter const > EventType
 
- Public Types inherited from message_filters::SimpleFilter< compass_msgs::Azimuth >
typedef boost::function< void(const MConstPtr &)> Callback
 
typedef boost::function< void(const EventType &)> EventCallback
 
typedef ros::MessageEvent< M const > EventType
 
typedef boost::shared_ptr< M const > MConstPtr
 

Public Member Functions

void add (const EventType &event)
 
void configFromParams (const cras::BoundParamHelper &params)
 Configure the subscriber from ROS parameters. More...
 
template<typename F >
void connectInput (F &f)
 
const ros::SubscribergetSubscriber () const
 Returns the internal ros::Subscriber. More...
 
std::string getTopic () const
 Get the name of the subscribed topic. More...
 
void setInputDefaults (const cras::optional< decltype(compass_msgs::Azimuth::orientation)> &orientation, const cras::optional< decltype(compass_msgs::Azimuth::reference)> &reference, const cras::optional< decltype(compass_msgs::Azimuth::variance)> &variance)
 Set defaults for inputs which do not support autodetection of various azimuth properties. More...
 
void subscribe () override
 Re-subscribe to a topic. More...
 
void subscribe (ros::NodeHandle &nh, const std::string &topic, uint32_t queueSize, const ros::TransportHints &transportHints, ros::CallbackQueueInterface *callbackQueue) override
 Subscribe to a topic. More...
 
 UniversalAzimuthSubscriber (const cras::LogHelperPtr &log, ros::NodeHandle &nh, const std::string &topic, uint32_t queueSize, const ros::TransportHints &transportHints={}, ros::CallbackQueueInterface *callbackQueue=nullptr)
 Constructor. More...
 
void unsubscribe () override
 Unsubscribe from the topic. More...
 
 ~UniversalAzimuthSubscriber () override
 
- Public Member Functions inherited from message_filters::SimpleFilter< compass_msgs::Azimuth >
const std::string & getName ()
 
Connection registerCallback (const boost::function< void(P)> &callback)
 
Connection registerCallback (const C &callback)
 
Connection registerCallback (void(*callback)(P))
 
Connection registerCallback (void(T::*callback)(P), T *t)
 
void setName (const std::string &name)
 
- Public Member Functions inherited from message_filters::SubscriberBase
virtual ~SubscriberBase ()
 
- Public Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 
 HasLogger (const ::cras::LogHelperPtr &log)
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 

Protected Member Functions

void cb (const EventType &event)
 
- Protected Member Functions inherited from message_filters::SimpleFilter< compass_msgs::Azimuth >
void signalMessage (const MConstPtr &msg)
 
void signalMessage (const ros::MessageEvent< M const > &event)
 

Protected Attributes

CompassConverter converter
 The azimuth message converter. More...
 
cras::optional< decltype(compass_msgs::Azimuth::orientation)> inputOrientation
 Orientation of the input azimuth (in case it is a data type which does not tell orientation explicitly). More...
 
cras::optional< decltype(compass_msgs::Azimuth::reference)> inputReference
 Reference of the input azimuth (in case it is a data type which does not tell reference explicitly). More...
 
cras::optional< decltype(compass_msgs::Azimuth::variance)> inputVariance
 Variance of the input azimuth (in case it is a data type which does not tell reference explicitly). More...
 
ros::NodeHandle nh
 The nodehandle to use for subscribing,. More...
 
ros::Subscriber sub
 The ROS subscriber. More...
 
ros::SubscribeOptions subscribeOps
 Options for recreating the subscriber. More...
 
- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 

Detailed Description

message_filters subscriber that can subscribe to various topic types and convert them all to an Azimuth message.

Currently supported types are: compass_msgs::Azimuth, geometry_msgs::PoseWithCovarianceStamped, geometry_msgs::QuaternionStamped, sensor_msgs::Imu.

Definition at line 44 of file message_filter.h.

Member Typedef Documentation

◆ EventType

Constructor & Destructor Documentation

◆ UniversalAzimuthSubscriber()

compass_conversions::UniversalAzimuthSubscriber::UniversalAzimuthSubscriber ( const cras::LogHelperPtr log,
ros::NodeHandle nh,
const std::string &  topic,
uint32_t  queueSize,
const ros::TransportHints transportHints = {},
ros::CallbackQueueInterface callbackQueue = nullptr 
)

Constructor.

Parameters
logLogger.
nhThe ros::NodeHandle to use for subscribing.
topicThe topic to subscribe to.
queueSizeQueue size of the subscription.
transportHintsThe transport hints to pass to the subscriber.
callbackQueueThe callback queue to attach to.

◆ ~UniversalAzimuthSubscriber()

compass_conversions::UniversalAzimuthSubscriber::~UniversalAzimuthSubscriber ( )
override

Member Function Documentation

◆ add()

void compass_conversions::UniversalAzimuthSubscriber::add ( const EventType event)

◆ cb()

void compass_conversions::UniversalAzimuthSubscriber::cb ( const EventType event)
protected

◆ configFromParams()

void compass_conversions::UniversalAzimuthSubscriber::configFromParams ( const cras::BoundParamHelper params)

Configure the subscriber from ROS parameters.

Parameters
[in]paramsROS 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. for QuaternionStamped).

◆ connectInput()

template<typename F >
void compass_conversions::UniversalAzimuthSubscriber::connectInput ( F &  f)
inline

Definition at line 135 of file message_filter.h.

◆ getSubscriber()

const ros::Subscriber& compass_conversions::UniversalAzimuthSubscriber::getSubscriber ( ) const

Returns the internal ros::Subscriber.

◆ getTopic()

std::string compass_conversions::UniversalAzimuthSubscriber::getTopic ( ) const

Get the name of the subscribed topic.

Returns
The topic name.

◆ setInputDefaults()

void compass_conversions::UniversalAzimuthSubscriber::setInputDefaults ( const cras::optional< decltype(compass_msgs::Azimuth::orientation)> &  orientation,
const cras::optional< decltype(compass_msgs::Azimuth::reference)> &  reference,
const cras::optional< decltype(compass_msgs::Azimuth::variance)> &  variance 
)

Set defaults for inputs which do not support autodetection of various azimuth properties.

Parameters
[in]orientationThe default orientation used if it cannot be detected.
[in]referenceThe reference used if it cannot be detected.
[in]varianceDefault variance used for topics which cannot automatically discover it.

◆ subscribe() [1/2]

void compass_conversions::UniversalAzimuthSubscriber::subscribe ( )
overridevirtual

Re-subscribe to a topic.

Implements message_filters::SubscriberBase.

◆ subscribe() [2/2]

void compass_conversions::UniversalAzimuthSubscriber::subscribe ( ros::NodeHandle nh,
const std::string &  topic,
uint32_t  queueSize,
const ros::TransportHints transportHints,
ros::CallbackQueueInterface callbackQueue 
)
overridevirtual

Subscribe to a topic.

If this Subscriber is already subscribed to a topic, this function will first unsubscribe.

Parameters
nhThe ros::NodeHandle to use for subscribing.
topicThe topic to subscribe to.
queueSizeQueue size of the subscription.
transportHintsThe transport hints to pass to the subscriber.
callbackQueueThe callback queue to attach to.

Implements message_filters::SubscriberBase.

◆ unsubscribe()

void compass_conversions::UniversalAzimuthSubscriber::unsubscribe ( )
overridevirtual

Unsubscribe from the topic.

Implements message_filters::SubscriberBase.

Member Data Documentation

◆ converter

CompassConverter compass_conversions::UniversalAzimuthSubscriber::converter
protected

The azimuth message converter.

Definition at line 147 of file message_filter.h.

◆ inputOrientation

cras::optional<decltype(compass_msgs::Azimuth::orientation)> compass_conversions::UniversalAzimuthSubscriber::inputOrientation
protected

Orientation of the input azimuth (in case it is a data type which does not tell orientation explicitly).

Definition at line 150 of file message_filter.h.

◆ inputReference

cras::optional<decltype(compass_msgs::Azimuth::reference)> compass_conversions::UniversalAzimuthSubscriber::inputReference
protected

Reference of the input azimuth (in case it is a data type which does not tell reference explicitly).

Definition at line 153 of file message_filter.h.

◆ inputVariance

cras::optional<decltype(compass_msgs::Azimuth::variance)> compass_conversions::UniversalAzimuthSubscriber::inputVariance
protected

Variance of the input azimuth (in case it is a data type which does not tell reference explicitly).

Definition at line 156 of file message_filter.h.

◆ nh

ros::NodeHandle compass_conversions::UniversalAzimuthSubscriber::nh
protected

The nodehandle to use for subscribing,.

Definition at line 146 of file message_filter.h.

◆ sub

ros::Subscriber compass_conversions::UniversalAzimuthSubscriber::sub
protected

The ROS subscriber.

Definition at line 144 of file message_filter.h.

◆ subscribeOps

ros::SubscribeOptions compass_conversions::UniversalAzimuthSubscriber::subscribeOps
protected

Options for recreating the subscriber.

Definition at line 145 of file message_filter.h.


The documentation for this class was generated from the following file:


compass_conversions
Author(s): Martin Pecka
autogenerated on Mon Dec 23 2024 04:03:21