Class ChangeHeaderNodelet
Defined in File change_header.h
Inheritance Relationships
Base Type
public cras::Nodelet
Class Documentation
-
class ChangeHeaderNodelet : public cras::Nodelet
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~inputtopic 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, theTCP_NODELAYflag 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 withfrom, it will be replaced withto.~frame_id_replace_end(string “from|to”, no default): If set and frame_id ends withfrom, it will be replaced withto.~frame_id_replace(string “from|to”, no default): If set, all occurrences offromin frame_id will be replaced withto.~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_relativewill 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_relativecan be used in combination with this option.
Subscribed topics:
~input(any type with header): The input messages. Iflazyis true, it will only be subscribed when~outputhas 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~inputtopic 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~outputtopic which is resolved against the private node(let) namespace). If not specified, output topic will be${TOPIC_IN}_relay.
Note
A copy of the received message will be made in any case to allow modification of the header. If you set frame_id to a longer string, another copy of the message will be made to make space for the prolonged ID.
Protected 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.
- Parameters:
event – [in] Event containing the received message.
pub – [in] The publisher to use for publishing.
Protected Attributes
-
::std::unique_ptr<::cras::GenericLazyPubSub> pubSub
The lazy pair of subscriber and publisher.
-
::cras::optional<::std::string> newFrameId
Replace the whole frame_id with this value.
-
::cras::optional<::std::string> newFrameIdPrefix
Prefix frame_id with this value.
-
::cras::optional<::std::string> newFrameIdSuffix
Suffix frame_id with this value.
-
::cras::optional<::std::pair<::std::string, ::std::string>> newFrameIdReplace
Replace all occurrences of first string with the second one in frame_id.
-
::cras::optional<::std::pair<::std::string, ::std::string>> newFrameIdReplaceStart
If frame_id starts with the first string, replace it with the second one.
-
::cras::optional<::std::pair<::std::string, ::std::string>> newFrameIdReplaceEnd
If frame_id ends with the first string, replace it with the second one.
-
::cras::optional<::ros::Time> newStampAbs
Replace stamp with the given value.
-
::cras::optional<::ros::Duration> newStampRel
Add this value to stamp. In case of under/overflow, TIME_MIN or TIME_MAX are set.
-
bool newStampRosTime = {false}
Change stamp to current ROS time.
-
bool newStampWallTime = {false}
Change stamp to current wall time.
-
::cras::optional<bool> hasHeader = {::cras::nullopt}
Whether the subscribed topic has a header field. This is filled on receipt of the first message.