Skip to content

Commit

Permalink
Fix cpplint formatting
Browse files Browse the repository at this point in the history
In 2 cases the formatting conflicts with what uncrustify wants; // NOLINT got rid of the complaints of cpplint, favouring uncrustify

Signed-off-by: Loy van Beek <loy.vanbeek@mojin-robotics.de>
  • Loading branch information
LoyVanBeek committed Oct 19, 2021
1 parent 68f63a4 commit fe2621d
Showing 1 changed file with 9 additions and 7 deletions.
16 changes: 9 additions & 7 deletions src/parameter_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <xmlrpcpp/XmlRpcException.h>

#include <list>
#include <string>

Expand All @@ -27,7 +29,6 @@

// include ROS 2
#include "rclcpp/rclcpp.hpp"
#include <xmlrpcpp/XmlRpcException.h>

#include "ros1_bridge/bridge.hpp"

Expand Down Expand Up @@ -57,7 +58,8 @@ rclcpp::QoS qos_from_params(XmlRpc::XmlRpcValue qos_params)
} else {
fprintf(
stderr,
"invalid value for 'history': '%s', allowed values are 'keep_all', 'keep_last' (also requires 'depth' to be set)\n",
"invalid value for 'history': '%s', allowed values are 'keep_all'," +
"'keep_last' (also requires 'depth' to be set)\n",
history.c_str());
}
}
Expand Down Expand Up @@ -163,18 +165,19 @@ rclcpp::QoS qos_from_params(XmlRpc::XmlRpcValue qos_params)
liveliness_str == "liveliness_system_default")
{
liveliness = rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT;
} else if (liveliness_str == "LIVELINESS_AUTOMATIC" ||
} else if (liveliness_str == "LIVELINESS_AUTOMATIC" || // NOLINT
liveliness_str == "liveliness_automatic")
{
liveliness = rmw_qos_liveliness_policy_t::RMW_QOS_POLICY_LIVELINESS_AUTOMATIC;
} else if (liveliness_str == "LIVELINESS_MANUAL_BY_TOPIC" ||
} else if (liveliness_str == "LIVELINESS_MANUAL_BY_TOPIC" || // NOLINT
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",
"invalid value for 'liveliness': '%s', allowed values are " +
"LIVELINESS_{SYSTEM_DEFAULT, AUTOMATIC, MANUAL_BY_TOPIC}, upper or lower case\n",
liveliness_str.c_str());
}

Expand Down Expand Up @@ -220,7 +223,7 @@ rclcpp::QoS qos_from_params(XmlRpc::XmlRpcValue qos_params)
} else {
fprintf(
stderr,
"QoS parameters could not be read\n"); // TODO: clearer message
"QoS parameters could not be read\n");
}

printf(")");
Expand Down Expand Up @@ -295,7 +298,6 @@ int main(int argc, char * argv[])
ros1_node, ros2_node, "", type_name, topic_name, queue_size);
all_handles.push_back(handles);
}

} catch (std::runtime_error & e) {
fprintf(
stderr,
Expand Down

0 comments on commit fe2621d

Please sign in to comment.