Nodelet for relaying messages and changing their header. More...
#include <change_header.h>
Protected Member Functions | |
void | onInit () override |
virtual void | processMessage (const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &event, ::ros::Publisher &pub) |
Change the header of the incoming message and publish the result. More... | |
Protected Member Functions inherited from nodelet::Nodelet | |
ros::CallbackQueueInterface & | getMTCallbackQueue () const |
ros::NodeHandle & | getMTNodeHandle () const |
ros::NodeHandle & | getMTPrivateNodeHandle () const |
const V_string & | getMyArgv () const |
const std::string & | getName () const |
ros::NodeHandle & | getNodeHandle () const |
ros::NodeHandle & | getPrivateNodeHandle () const |
const M_string & | getRemappingArgs () const |
ros::CallbackQueueInterface & | getSTCallbackQueue () const |
std::string | getSuffixedName (const std::string &suffix) const |
Protected Member Functions inherited from NodeletWithDiagnostics< ::nodelet::Nodelet > | |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &topic, size_t queueSize, bool latch=false) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, ros::AdvertiseOptions &options) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &topic, size_t queueSize, bool latch=false) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ros::AdvertiseOptions &options) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (const ::std::string &topic, size_t queueSize, bool latch=false) |
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (ros::AdvertiseOptions &options) |
CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",)) | |
CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(defaultDiagParams, diagNamespace,)) | |
CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,)) | |
CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh,), CRAS_SINGLE_ARG(subscriberNh, diagNh,), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",)) | |
CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh,), CRAS_SINGLE_ARG(subscriberNh, diagNh,), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,)) | |
CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, ""),), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",)) | |
CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, diagNamespace),), CRAS_SINGLE_ARG(const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(defaultDiagParams, diagNamespace,)) | |
CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, diagNamespace),), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,)) | |
::std::unique_ptr<::cras::DiagnosedPublisher< T > > | createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string ¶mNamespace) |
::std::unique_ptr<::cras::DiagnosedPublisher< T > > | createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string ¶mNamespace, const ::ros::Rate &defaultRate) |
::std::unique_ptr<::cras::DiagnosedPublisher< T > > | createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string ¶mNamespace, const ::ros::Rate &defaultRate, const ::ros::Rate &defaultMinRate, const ::ros::Rate &defaultMaxRate) |
::ros::NodeHandle | getDefaultDiagNh (const ::ros::NodeHandle &pubSubNh, const ::std::string &diagNamespace) |
::cras::BoundParamHelperPtr | getDiagParams (const ::ros::NodeHandle &nh, const ::std::string &diagNamespace, const ::std::string &topic) |
::cras::DiagnosticUpdater & | getDiagUpdater (bool forceNew=false) const |
void | startDiagTimer () const |
void | startDiagTimer (const ::ros::NodeHandle &nh) const |
void | stopDiagTimer () const |
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::SubscribeOptions &options) |
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const ::boost::function< void(const ::boost::shared_ptr< Message > &)> &cb, ::ros::TransportHints hints={}) |
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< C > > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< C >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const ::boost::function< void(C)> &cb, ::ros::VoidConstPtr obj={}, ::ros::TransportHints hints={}) |
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints={}) |
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={}) |
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, T *obj, ::ros::TransportHints hints={}) |
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={}) |
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), T *obj, ::ros::TransportHints hints={}) |
Protected Member Functions inherited from cras::TimeJumpResettable | |
void | checkTimeJump () |
virtual void | checkTimeJump (const ::ros::Time &now) |
void | initRos (const ::ros::NodeHandle &pnh) override |
void | startAutoCheckTimeJump () |
virtual void | startAutoCheckTimeJump (const ::ros::WallRate &rate) |
virtual void | stopAutoCheckTimeJump () |
TimeJumpResettable (const ::cras::LogHelperPtr &log) | |
~TimeJumpResettable () override | |
Protected Member Functions inherited from cras::Resettable | |
Resettable (const ::cras::LogHelperPtr &log) | |
virtual | ~Resettable () |
Protected Member Functions inherited from ThreadNameUpdatingNodelet< ::nodelet::Nodelet > | |
void | updateThreadName () const |
Protected Member Functions inherited from NodeletParamHelper< ::nodelet::Nodelet > | |
inline ::std::string | getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) |
ResultType | getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) |
inline ::std::string | getParam (const ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) |
ResultType | getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) |
inline ::cras::GetParamResult<::std::string > | getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) |
inline ::cras::GetParamResult< ResultType > | getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) |
inline ::cras::GetParamResult<::std::string > | getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) |
inline ::cras::GetParamResult< ResultType > | getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) |
::cras::BoundParamHelperPtr | params (const ::ros::NodeHandle &node, const ::std::string &ns="") const |
::cras::BoundParamHelperPtr | paramsForNodeHandle (const ::ros::NodeHandle &node) const |
::cras::BoundParamHelperPtr | privateParams (const ::std::string &ns="") const |
::cras::BoundParamHelperPtr | publicParams (const ::std::string &ns="") const |
Protected Attributes | |
::cras::optional< bool > | hasHeader {::cras::nullopt} |
Whether the subscribed topic has a header field. This is filled on receipt of the first message. More... | |
::cras::optional<::std::string > | newFrameId |
Replace the whole frame_id with this value. More... | |
::cras::optional<::std::string > | newFrameIdPrefix |
Prefix frame_id with this value. More... | |
::cras::optional<::std::pair<::std::string, ::std::string > > | newFrameIdReplace |
Replace all occurrences of first string with the second one in frame_id. More... | |
::cras::optional<::std::pair<::std::string, ::std::string > > | newFrameIdReplaceEnd |
If frame_id ends with the first string, replace it with the second one. More... | |
::cras::optional<::std::pair<::std::string, ::std::string > > | newFrameIdReplaceStart |
If frame_id starts with the first string, replace it with the second one. More... | |
::cras::optional<::std::string > | newFrameIdSuffix |
Suffix frame_id with this value. More... | |
::cras::optional<::ros::Time > | newStampAbs |
Replace stamp with the given value. More... | |
::cras::optional<::ros::Duration > | newStampRel |
Add this value to stamp. In case of under/overflow, TIME_MIN or TIME_MAX are set. More... | |
bool | newStampRosTime {false} |
Change stamp to current ROS time. More... | |
bool | newStampWallTime {false} |
Change stamp to current wall time. More... | |
::std::unique_ptr<::cras::GenericLazyPubSub > | pubSub |
The lazy pair of subscriber and publisher. More... | |
Protected Attributes inherited from cras::HasLogger | |
::cras::LogHelperPtr | log |
Protected Attributes inherited from cras::InterruptibleSleepInterface | |
::ros::WallDuration | pollDuration |
Additional Inherited Members | |
Public Member Functions inherited from cras::Nodelet | |
~Nodelet () override=default | |
Public Member Functions inherited from NodeletBase<::nodelet::Nodelet > | |
~NodeletBase () override=default | |
Public Member Functions inherited from nodelet::Nodelet | |
void | init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL) |
Nodelet () | |
Public Member Functions inherited from NodeletWithDiagnostics< ::nodelet::Nodelet > | |
NodeletWithDiagnostics () | |
virtual | ~NodeletWithDiagnostics () |
Public Member Functions inherited from NodeletWithSharedTfBuffer< ::nodelet::Nodelet > | |
::cras::NodeletAwareTFBuffer & | getBuffer () const override |
NodeletWithSharedTfBuffer () | |
void | reset () override |
void | setBuffer (const ::std::shared_ptr<::tf2_ros::Buffer > &buffer) override |
bool | usesSharedBuffer () const override |
virtual | ~NodeletWithSharedTfBuffer () |
Public Member Functions inherited from ThreadNameUpdatingNodelet< ::nodelet::Nodelet > | |
~ThreadNameUpdatingNodelet () override | |
Public Member Functions inherited from NodeletParamHelper< ::nodelet::Nodelet > | |
NodeletParamHelper () | |
~NodeletParamHelper () override | |
Public Member Functions inherited from cras::ParamHelper | |
::cras::LogHelperPtr | getLogger () const |
inline ::std::string | getParam (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const |
ResultType | getParam (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const |
inline ::std::string | getParam (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const |
ResultType | getParam (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const |
inline ::cras::GetParamResult<::std::string > | getParamVerbose (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const |
inline ::cras::GetParamResult< ResultType > | getParamVerbose (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const |
inline ::cras::GetParamResult<::std::string > | getParamVerbose (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const |
inline ::cras::GetParamResult< ResultType > | getParamVerbose (const ::cras::GetParamAdapter ¶m, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const |
ParamHelper (const ::cras::LogHelperPtr &log) | |
void | setLogger (const ::cras::LogHelperPtr &logger) |
virtual | ~ParamHelper ()=default |
Public Member Functions inherited from cras::HasLogger | |
::cras::LogHelperConstPtr | getCrasLogger () const |
HasLogger (const ::cras::LogHelperPtr &log) | |
void | setCrasLogger (const ::cras::LogHelperPtr &log) |
Public Member Functions inherited from StatefulNodelet< ::nodelet::Nodelet > | |
bool | ok () const override |
void | requestStop () override |
void | shutdown () |
virtual | ~StatefulNodelet () |
Public Member Functions inherited from cras::InterruptibleSleepInterface | |
InterruptibleSleepInterface () | |
virtual bool | sleep (const ::ros::Duration &duration) const |
virtual | ~InterruptibleSleepInterface () |
Nodelet for relaying messages and changing their header.
ROS parameters:
~in_queue_size
(uint, default 10): Queue size for the subscriber.~out_queue_size
(uint, default $in_queue_size): Queue size for the publisher.~lazy
(bool, default False): Whether to shut down the subscriber when the publisher has no subscribers. The ~input
topic will be subscribed in the beginning, and will unsubscribe automatically after the first message is received (this is needed to determine the full type of the topic to publish).~tcp_no_delay
(bool, default False): If True, the TCP_NODELAY
flag is set for the subscriber. This should decrease the latency of small messages, but might give suboptimal transmission speed for large messages.~frame_id_prefix
(string, no default): If set, frame_id will be prefixed with this string.~frame_id_suffix
(string, no default): If set, frame_id will be suffixed with this string.~frame_id
(string, no default): If set, frame_id will be replaced by this string.~frame_id_replace_start
(string "from|to", no default): If set and frame_id starts with from
, it will be replaced with to
.~frame_id_replace_end
(string "from|to", no default): If set and frame_id ends with from
, it will be replaced with to
.~frame_id_replace
(string "from|to", no default): If set, all occurrences of from
in frame_id will be replaced with to
.~stamp_relative
(double, no default): If set, the given duration will be added to the message's stamp. If the stamp would under/overflow, ros::TIME_MIN or ros::TIME_MAX will be set.~stamp
(double, no default): If set, the message's stamp will be set to this time (stamp_relative
will not apply if set).~stamp_ros_time (bool, default false): If true, message stamp will be changed to current ROS time.
stamp_relativecan be used in combination with this option. -
~stamp_wall_time (bool, default false): If true, message stamp will be changed to current wall time. stamp_relative
can be used in combination with this option.Subscribed topics:
~input
(any type with header): The input messages. If lazy
is true, it will only be subscribed when ~output
has some subscribers. If you subscribe to a message type without header, the node should not crash, but it will discard all received messages and print an error message.Published topics:
~output
(same type as ~input
): The relayed output messages with changed header.Command-line arguments: This nodelet (or node) can also be called in a way backwards compatible with topic_tools/relay. This means you can pass CLI arguments specifying the topics to subscribe/publish.
rosrun cras_topic_tools relay TOPIC_IN [TOPIC_OUT]
TOPIC_IN
: The topic to subscribe. It is resolved against parent namespace of the node(let) (as opposed to the ~input
topic which is resolved against the private node(let) namespace).TOPIC_OUT
: The topic to publish. It is resolved against parent namespace of the node(let) (as opposed to the ~output
topic which is resolved against the private node(let) namespace). If not specified, output topic will be ${TOPIC_IN}_relay
.Definition at line 84 of file change_header.h.
|
overrideprotectedvirtual |
Reimplemented from NodeletBase<::nodelet::Nodelet >.
Definition at line 32 of file change_header.cpp.
|
protectedvirtual |
Change the header of the incoming message and publish the result.
[in] | event | Event containing the received message. |
[in] | pub | The publisher to use for publishing. |
Definition at line 110 of file change_header.cpp.
|
protected |
Whether the subscribed topic has a header field. This is filled on receipt of the first message.
Definition at line 131 of file change_header.h.
|
protected |
Replace the whole frame_id with this value.
Definition at line 101 of file change_header.h.
|
protected |
Prefix frame_id with this value.
Definition at line 104 of file change_header.h.
|
protected |
Replace all occurrences of first string with the second one in frame_id.
Definition at line 110 of file change_header.h.
|
protected |
If frame_id ends with the first string, replace it with the second one.
Definition at line 116 of file change_header.h.
|
protected |
If frame_id starts with the first string, replace it with the second one.
Definition at line 113 of file change_header.h.
|
protected |
Suffix frame_id with this value.
Definition at line 107 of file change_header.h.
|
protected |
Replace stamp with the given value.
Definition at line 119 of file change_header.h.
|
protected |
Add this value to stamp. In case of under/overflow, TIME_MIN or TIME_MAX are set.
Definition at line 122 of file change_header.h.
|
protected |
Change stamp to current ROS time.
Definition at line 125 of file change_header.h.
|
protected |
Change stamp to current wall time.
Definition at line 128 of file change_header.h.
|
protected |
The lazy pair of subscriber and publisher.
Definition at line 88 of file change_header.h.