message_filters subscriber that can subscribe to various topic types and convert them all to an Azimuth message. More...
#include <message_filter.h>

Public Types | |
| typedef ros::MessageEvent< topic_tools::ShapeShifter const > | EventType |
Public Member Functions | |
| void | add (const EventType &event) |
| void | configFromParams (const cras::BoundParamHelper ¶ms) |
| Configure the subscriber from ROS parameters. More... | |
| template<typename F > | |
| void | connectInput (F &f) |
| const ros::Subscriber & | getSubscriber () 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 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 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 |
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.
| typedef ros::MessageEvent<topic_tools::ShapeShifter const> compass_conversions::UniversalAzimuthSubscriber::EventType |
Definition at line 49 of file message_filter.h.
| 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.
| log | Logger. |
| nh | The ros::NodeHandle to use for subscribing. |
| topic | The topic to subscribe to. |
| queueSize | Queue size of the subscription. |
| transportHints | The transport hints to pass to the subscriber. |
| callbackQueue | The callback queue to attach to. |
|
override |
| void compass_conversions::UniversalAzimuthSubscriber::add | ( | const EventType & | event | ) |
|
protected |
| void compass_conversions::UniversalAzimuthSubscriber::configFromParams | ( | const cras::BoundParamHelper & | params | ) |
Configure the subscriber from ROS parameters.
| [in] | params | 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. for QuaternionStamped).
|
inline |
Definition at line 135 of file message_filter.h.
| const ros::Subscriber& compass_conversions::UniversalAzimuthSubscriber::getSubscriber | ( | ) | const |
Returns the internal ros::Subscriber.
| std::string compass_conversions::UniversalAzimuthSubscriber::getTopic | ( | ) | const |
Get the name of the subscribed topic.
| 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.
| [in] | orientation | The default orientation used if it cannot be detected. |
| [in] | reference | The reference used if it cannot be detected. |
| [in] | variance | Default variance used for topics which cannot automatically discover it. |
|
overridevirtual |
Re-subscribe to a topic.
Implements message_filters::SubscriberBase.
|
overridevirtual |
Subscribe to a topic.
If this Subscriber is already subscribed to a topic, this function will first unsubscribe.
| nh | The ros::NodeHandle to use for subscribing. |
| topic | The topic to subscribe to. |
| queueSize | Queue size of the subscription. |
| transportHints | The transport hints to pass to the subscriber. |
| callbackQueue | The callback queue to attach to. |
Implements message_filters::SubscriberBase.
|
overridevirtual |
Unsubscribe from the topic.
Implements message_filters::SubscriberBase.
|
protected |
The azimuth message converter.
Definition at line 147 of file message_filter.h.
|
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.
|
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.
|
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.
|
protected |
The nodehandle to use for subscribing,.
Definition at line 146 of file message_filter.h.
|
protected |
The ROS subscriber.
Definition at line 144 of file message_filter.h.
|
protected |
Options for recreating the subscriber.
Definition at line 145 of file message_filter.h.