Skip to content

Commit

Permalink
Parse liveliness as either int enum value or upper/lower case string …
Browse files Browse the repository at this point in the history
…representation of liveliness enum values

Signed-off-by: Loy van Beek <loy.vanbeek@mojin-robotics.de>
  • Loading branch information
LoyVanBeek committed Oct 18, 2021
1 parent 6f13f2c commit a7b4cb2
Show file tree
Hide file tree
Showing 2 changed files with 108 additions and 13 deletions.
42 changes: 42 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -419,3 +419,45 @@ This should start printing text like `I heard: [hello world ...]` with a timesta
ros2 service call /add_two_ints example_interfaces/srv/AddTwoInts "{a: 1, b: 2}"
```
If all is well, the output should contain `example_interfaces.srv.AddTwoInts_Response(sum=3)`

### Parametrizing Quality of Service
An advantage or ROS 2 over ROS 1 is the possibility to define different Quality of Service settings per topic.
The parameter bridge optionally allows for this as well: the `qos` section can be omitted entirely and options not set are left default.
For some topics, like `/tf_static` this is actually required, as this is a latching topic in ROS 1.
In ROS 2 with the `parameter_bridge`, this requires that topic to be configured as such:

```yaml
topics:
-
topic: /tf_static
type: tf2_msgs/msg/TFMessage
queue_size: 1
qos:
history: keep_all
durability: transient_local
```
All other QoS options (as documented here in https://docs.ros.org/en/foxy/Concepts/About-Quality-of-Service-Settings.html) are available:
```yaml
topics:
-
topic: /some_ros1_topic
type: std_msgs/msg/String
queue_size: 1
qos:
history: keep_last # OR keep_last, then you can omit `depth` below
depth: 10 # Only required when history == keep_last
reliability: reliable # OR best_effort
durability: transient_local # OR volatile
deadline:
secs: 10
nsecs: 2345
lifespan:
secs: 20
nsecs: 3456
liveliness: liveliness_system_default # Values from https://design.ros2.org/articles/qos_deadline_liveliness_lifespan.html, eg. LIVELINESS_AUTOMATIC
liveliness_lease_duration:
secs: 40
nsecs: 5678
```
79 changes: 66 additions & 13 deletions src/parameter_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,25 +169,78 @@ rclcpp::QoS qos_from_params(XmlRpc::XmlRpcValue qos_params)

if (qos_params.hasMember("liveliness"))
{
try
if (qos_params["liveliness"].getType() == XmlRpc::XmlRpcValue::TypeInt)
{
auto liveliness = static_cast<int>(qos_params["liveliness"]);
ros2_publisher_qos.liveliness(static_cast<rmw_qos_liveliness_policy_t>(liveliness));
printf("liveliness: %i, ", static_cast<int>(liveliness));
printf("liviness is an int\n");
try
{
auto liveliness = static_cast<int>(qos_params["liveliness"]);
ros2_publisher_qos.liveliness(static_cast<rmw_qos_liveliness_policy_t>(liveliness));
printf("liveliness: %i, ", static_cast<int>(liveliness));
}
catch (std::runtime_error &e)
{
fprintf(
stderr,
"failed to create parametrize liveliness: '%s'\n",
e.what());
}
catch (XmlRpc::XmlRpcException &e)
{
fprintf(
stderr,
"failed to create parametrize liveliness: '%s'\n",
e.getMessage().c_str());
}
}
catch (std::runtime_error &e)
else if (qos_params["liveliness"].getType() == XmlRpc::XmlRpcValue::TypeString)
{
fprintf(
stderr,
"failed to create parametrize liveliness: '%s'\n",
e.what());
try
{
rmw_qos_liveliness_policy_t liveliness = rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT;
auto liveliness_str = static_cast<std::string>(qos_params["liveliness"]);
if (liveliness_str == "LIVELINESS_SYSTEM_DEFAULT" || liveliness_str == "liveliness_system_default")
{
liveliness = rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT;
}
else if (liveliness_str == "LIVELINESS_AUTOMATIC" || liveliness_str == "liveliness_automatic")
{
liveliness = rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
}
else if (liveliness_str == "LIVELINESS_MANUAL_BY_TOPIC" || liveliness_str == "liveliness_manual_by_topic")
{
liveliness = rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC;
}
else
{
fprintf(
stderr,
"invalid value for 'liveliness': '%s', allowed values are LIVELINESS_{SYSTEM_DEFAULT, AUTOMATIC, MANUAL_BY_TOPIC}, upper or lower case\n", liveliness_str.c_str());
}

ros2_publisher_qos.liveliness(liveliness);
printf("liveliness: %s, ", liveliness_str.c_str());
}
catch (std::runtime_error &e)
{
fprintf(
stderr,
"failed to create parametrize liveliness: '%s'\n",
e.what());
}
catch (XmlRpc::XmlRpcException &e)
{
fprintf(
stderr,
"failed to create parametrize liveliness: '%s'\n",
e.getMessage().c_str());
}
}
catch (XmlRpc::XmlRpcException &e)
else
{
fprintf(
stderr,
"failed to create parametrize liveliness: '%s'\n",
e.getMessage().c_str());
stderr,
"failed to create parametrize liveliness, parameter was not a string or int \n");
}
}

Expand Down

0 comments on commit a7b4cb2

Please sign in to comment.