inorbit_republisher package from ros_inorbit_samples repoinorbit_republisher |
|
Package Summary
Tags | No category tags. |
Version | 0.3.2 |
License | MIT |
Build type | CATKIN |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/inorbit-ai/ros_inorbit_samples.git |
VCS Type | git |
VCS Version | noetic-devel |
Last Updated | 2024-11-20 |
Dev Status | MAINTAINED |
CI status | Continuous Integration : 0 / 0 |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- InOrbit
Authors
InOrbit republisher for ROS 1
This directory includes a republisher that allows mapping from arbitrary ROS values to InOrbit
custom data key/value pairs for application-specific observability.
Currently only mapping from ROS topics is supported. The republisher could be extended to map actions, services and parameters.
Usage
Create a YAML config file specifying the mappings you would like to use using this format:
republishers:
- topic: "/fruits_per_cubic_m"
msg_type: "fruit_msgs/Citrus"
mappings:
- field: "num_oranges"
mapping_type: "single_field"
out:
topic: "/inorbit/custom_data/0"
key: "oranges"
- topic: "/hardware/status"
msg_type: "hw_msgs/HardwareStatus"
mappings:
- field: "status"
mapping_options:
fields: ["lidar", "motor", "battery"]
filter: 'lambda x: (x.status == 1)'
mapping_type: "array_of_fields"
out:
topic: "/inorbit/custom_data/0"
key: "hardware_error"
- topic: "/cmd_vel"
msg_type: "geometry_msgs/Twist"
mappings:
- field: "linear"
mapping_type: "json_of_fields"
mapping_options:
fields: ["x", "y", "z"]
out:
topic: "/inorbit/linear_vel_test"
key: "linear_vel"
- topic: "/map_metadata"
latched: true
msg_type: "nav_msgs/MapMetaData"
mappings:
- field: "resolution"
mapping_type: "single_field"
out:
topic: "/inorbit/map_res_test"
key: "map_resolution"
- topic: "/navsat"
msg_type: "sensor_msgs/NavSatFix"
mappings:
- mapping_type: "serialize"
mapping_options:
fields: ["status", "latitude", "longitude", "position_covariance_type"]
out:
topic: "/inorbit/custom_data/0"
key: "navsat"
static_publishers:
- value: "this is a fixed string"
out:
topic: "/inorbit/custom_data/0"
key: "greeting"
- value_from:
environment_variable: "PATH"
out:
topic: "/inorbit/custom_data/0"
key: "env_path"
Then launch the republisher.py
script passing the config file as the config
param.
A suggested way to organize this is by creating the config file and launch file in your package, then the corresponding launch file would like like this:
<launch>
<node name="inorbit_republisher" pkg="inorbit_republisher" type="republisher.py">
<param name="config" textfile="$(find inorbit_republisher)/config/example.yaml" />
</node>
</launch>
Mapping ROS topics
The republisher can map the ROS values to single field (e.g. 'fruit=apple'
) or to an array of fields (e.g. 'fruits=[{fruit1: apple, fruit2: orange}, {fruit1: melon, fruit2: apple}]'
). The former is useful to capture simple fields and the latter to get data from an array of values.
Single field: mapping options
When republishing a single field, you can include a set of mapping_options
for each mapping
. These include:
-
mapping_type
: this mapping option should be set tosingle_field
. -
filter
: a lambda expression that can be used to control whether or not the value is published based on a condition. For example, if you’d like to republish only String values that are different thanSPAMMY STRING
, you can do it with:
mapping_options:
filter: 'lambda x: (x != "SPAMMY STRING")'
Array of fields: mapping options
When republishing an array of fields, you can include a set of mapping_options
for each mapping
. These include:
-
mapping_type
: this mapping option should be set toarray_of_fields
. -
fields
: a set of fields that you’d like to capture from each array element. For example, if each array element contains the elements[a, c, d, e]
and you’d like to geta
andc
only, you can specify it as:
mapping_options:
fields: ["a", "c"]
If no fields are specified, the republisher will get all the fields in each array element.
-
filter
: a lambda expression that can be used to pick certain array elements based on a condition. For example, if you’d like to republish array elements wherec > 5
only, you can do it with:
mapping_options:
filter: 'lambda x: (x > 5)'
JSON of fields: mapping options
When republishing several fields of a nested structure, this mapping type allows to bundle them together in a single JSON message instead of republishing all the fields of interest separately.
The mapping_options
for this type include:
-
mapping_type
: this mapping option should be set tojson_of_fields
. -
fields
: a set of fields that you’d like to capture from the nested message. For example, if your message definition looks like Twist:setting
mapping_options:
fields: ["x", "y", "z"]
would output a JSON object with the fields as keys with their respective values for the message
data: "linear_vel={\"y\": 0.00013548378774430603, \"x\": 0.0732172280550003, \"z\": 0.0}"
-
filter
: a lambda expression that can be used to control whether or not the JSON object is published based on a condition. For example, if you’d like to republish only JSON objects that have a value for the keyz
different than0
, you can do it with:
mapping_options:
filter: 'lambda linear_vel: (linear_vel["z"] != 0)'
Serialize: mapping options
This mapping option transforms the entire ROS message to a JSON string.
The mapping_options
for this type include:
-
mapping_type
: this mapping option should be set toserialize
. -
fields
: (optional) a set of first level fields or keys to keep. If not provided, all fields are kept. For example, using the following mapping option for serializing 4 NavSatFix fields:
mapping_options:
fields: ["status", "latitude", "longitude", "position_covariance_type"]
would output a JSON object with the fields as keys with their respective values for the message
data: "navsat={\"status\": {\"status\": 0, \"service\": 0}, \"latitude\": 0.0, \"longitude\" : 0.0, \"position_covariance_type\": 0}"
Publishing fixed values
Sometimes it is also useful to publish fixed values to facilitate fleet-wide observability. It is possible to publish environment variables, package versions or fixed values using the static_publishers
array.
See the included example configuration in config/example.yaml
for specific examples.
These values will be published as latched and delivered only once every time a subscriber connects to the republisher.
Publishing latched values
Republishing latched topics requires a special treatment to make sure that all latched messages, from each mapping defined, get published when a new subscriber connects to the output topic (this case is prone to subscription issues depending on nodes startup timing). To achieve this, add a flag to the input topic config indicating that it is latched:
republishers:
- topic: "/map_metadata"
latched: true
Building and running locally
Find below instructions for building the package and running the node using the the code on the workspace (see also catkin).
Start ROS2 docker container (optional)
You can run the commands below for building and running the republisher inside a docker container.
docker run -ti --rm \
--workdir /root/catkin_ws/ \
-v .:/root/catkin_ws/src/inorbit_republisher \
osrf/ros:noetic-desktop
# Install catkin
apt update && apt install python3-catkin-tools python3-osrf-pycommon -y
Build
cd ~/catkin_ws
rosdep install --from-paths ~/catkin_ws/src --ignore-src --rosdistro=noetic
catkin clean
catkin build inorbit_republisher --verbose
Run
. ~/catkin_ws/devel/setup.bash
# Using the launch file under the 'launch' directory
roslaunch inorbit_republisher example.launch
TODO
- Schema validation
- Better documentation
- Error handling
- Proper logging
- Latched topic support
- Mapping of ROS parameters
Changelog for package inorbit_republisher
0.3.2 (2024-11-20)
- Fix LatchPublisher publish to handle ROS String messages (#26)
- Contributors: Leandro
0.3.1 (2024-11-13)
- Fix LatchPublisher peer_subscribe to publish all key-values (#25)
- Contributors: Leandro
0.3.0 (2023-06-03) -----------* Add an explicit latched property for republishers (#17) * Contributors: mechatheo
0.2.5 (2022-08-24) -----------* Add filtering in JSON mappings (#14) * Contributors: Elvio_Aruta
0.2.4 (2022-02-21) -----------* Add conditionals in package.xml dependencies (#11) * Contributors: Flor_Grosso
0.2.3 (2022-02-21) -----------* Allow filtering single_value mappings (#5) * Allow publishing package versions, environment variables or fixed strings (#5) * Allow using config_file parameter instead of config (#5) * Contributors: adamantivm
0.2.2 (2021-12-07) -----------* Add support for JSON of fields * Contributors: Flor_Grosso
0.2.1 (2021-07-20)
- Initial Implementation
- Contributors: Leandro Pineda
Wiki Tutorials
Package Dependencies
System Dependencies
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged inorbit_republisher at Robotics Stack Exchange
inorbit_republisher package from ros_inorbit_samples repoinorbit_republisher |
|
Package Summary
Tags | No category tags. |
Version | 0.2.5 |
License | MIT |
Build type | CATKIN |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/inorbit-ai/ros_inorbit_samples.git |
VCS Type | git |
VCS Version | melodic-devel |
Last Updated | 2022-08-25 |
Dev Status | MAINTAINED |
CI status | Continuous Integration : 0 / 0 |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- InOrbit
Authors
InOrbit republisher for ROS 1
This directory includes a republisher that allows mapping from arbitrary ROS values to InOrbit
custom data key/value pairs for application-specific observability.
Currently only mapping from ROS topics is supported. The republisher could be extended to map actions, services and parameters.
Usage
Create a YAML config file specifying the mappings you would like to use using this format:
republishers:
- topic: "/fruits_per_cubic_m"
msg_type: "fruit_msgs/Citrus"
mappings:
- field: "num_oranges"
mapping_type: "single_field"
out:
topic: "/inorbit/custom_data/0"
key: "oranges"
- topic: "/hardware/status"
msg_type: "hw_msgs/HardwareStatus"
mappings:
- field: "status"
mapping_options:
fields: ["lidar", "motor", "battery"]
filter: 'lambda x: (x.status == 1)'
mapping_type: "array_of_fields"
out:
topic: "/inorbit/custom_data/0"
key: "hardware_error"
- topic: "/cmd_vel"
msg_type: "geometry_msgs/Twist"
mappings:
- field: "linear"
mapping_type: "json_of_fields"
mapping_options:
fields: ["x", "y", "z"]
out:
topic: "/inorbit/linear_vel_test"
key: "linear_vel"
static_publishers:
- value: "this is a fixed string"
out:
topic: "/inorbit/custom_data/0"
key: "greeting"
- value_from:
environment_variable: "PATH"
out:
topic: "/inorbit/custom_data/0"
key: "env_path"
Then launch the republisher.py
script passing the config file as the config
param.
A suggested way to organize this is by creating the config file and launch file in your package, then the corresponding launch file would like like this:
<launch>
<node name="inorbit_republisher" pkg="inorbit_republisher" type="republisher.py">
<param name="config" textfile="$(find inorbit_republisher)/config/example.yaml" />
</node>
</launch>
Mapping ROS topics
The republisher can map the ROS values to single field (e.g. 'fruit=apple'
) or to an array of fields (e.g. 'fruits=[{fruit1: apple, fruit2: orange}, {fruit1: melon, fruit2: apple}]'
). The former is useful to capture simple fields and the latter to get data from an array of values.
Single field: mapping options
When republishing a single field, you can include a set of mapping_options
for each mapping
. These include:
-
filter
: a lambda expression that can be used to control whether or not the value is published based on a condition. For example, if you’d like to republish only String values that are different thanSPAMMY STRING
, you can do it with:
mapping_options:
filter: 'lambda x: (x != "SPAMMY STRING")'
Array of fields: mapping options
When republishing an array of fields, you can include a set of mapping_options
for each mapping
. These include:
-
fields
: a set of fields that you’d like to capture from each array element. For example, if each array element contains the elements[a, c, d, e]
and you’d like to geta
andc
only, you can specify it as:
mapping_options:
fields: ["a", "c"]
If no fields are specified, the republisher will get all the fields in each array element.
-
filter
: a lambda expression that can be used to pick certain array elements based on a condition. For example, if you’d like to republish array elements wherec > 5
only, you can do it with:
mapping_options:
filter: 'lambda x: (x > 5)'
JSON of fields: mapping options
When republishing several fields of a nested structure, this mapping type allows to bundle them together in a single JSON message instead of republishing all the fields of interest separately.
The mapping_options
for this type include:
-
fields
: a set of fields that you’d like to capture from the nested message. For example, if your message definition looks like Twist:setting
mapping_options:
fields: ["x", "y", "z"]
would output a JSON object with the fields as keys with their respective values for the message
data: "linear_vel={\"y\": 0.00013548378774430603, \"x\": 0.0732172280550003, \"z\": 0.0}"
-
filter
: a lambda expression that can be used to control whether or not the JSON object is published based on a condition. For example, if you’d like to republish only JSON objects that have a value for the keyz
different than0
, you can do it with:
mapping_options:
filter: 'lambda linear_vel: (linear_vel["z"] != 0)'
Publishing fixed values
Sometimes it is also useful to publish fixed values to facilitate fleet-wide observability. It is possible to publish environment variables, package versions or fixed values using the static_publishers
array.
See the included example configuration in config/example.yaml
for specific examples.
These values will be published as latched and delivered only once every time a subscriber connects to the republisher.
Building and running locally
Find below instructions for building the package and running the node using the the code on the workspace (see also catkin).
Build
cd ~/catkin_ws
rosdep install --from-paths ~/catkin_ws/src --ignore-src --rosdistro=melodic
catkin clean
catkin build inorbit_republisher --verbose
Run
. ~/catkin_ws/install/setup.zsh
# Using the launch file under the 'launch' directory
roslaunch launch/example.launch
TODO
- Schema validation
- Better documentation
- Error handling
- Proper logging
- Latched topic support
- Mapping of ROS parameters
Changelog for package inorbit_republisher
0.2.5 (2022-08-24) -----------* Add filtering in JSON mappings (#14) * Contributors: Elvio_Aruta
0.2.4 (2022-02-21) -----------* Add conditionals in package.xml dependencies (#11) * Contributors: FlorGrosso
0.2.3 (2022-02-21) -----------* Allow filtering single_value mappings (#8) * Allow publishing package versions, environment variables or fixed strings (#8) * Allow using config_file parameter instead of config (#8) * Contributors: adamantivm
0.2.2 (2021-12-07) -----------* Add support for JSON of fields * Contributors: FlorGrosso
0.2.1 (2021-07-20)
- Initial Implementation
- Contributors: Leandro Pineda