Skip to content

Commit

Permalink
Incorporate the review comments.
Browse files Browse the repository at this point in the history
Signed-off-by: ChenYing Kuo <[email protected]>
  • Loading branch information
evshary committed Oct 25, 2024
1 parent 1b031ec commit aa68eb3
Showing 1 changed file with 7 additions and 0 deletions.
7 changes: 7 additions & 0 deletions ros_gz_sim/src/create.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -158,11 +158,13 @@ int main(int _argc, char ** _argv)

if (!executed) {
RCLCPP_INFO(ros2_node->get_logger(), "Timed out when getting world names.");
rclcpp::shutdown();
return -1;
}

if (!result || worlds_msg.data().empty()) {
RCLCPP_INFO(ros2_node->get_logger(), "Failed to get world names.");
rclcpp::shutdown();
return -1;
}

Expand All @@ -185,6 +187,7 @@ int main(int _argc, char ** _argv)
} else if (!topic_name.empty()) {
// set XML string by fetching it from the given topic
if (!set_XML_from_topic(topic_name, ros2_node, req)) {
rclcpp::shutdown();
return -1;
}
} else if (filtered_arguments.size() > 1) {
Expand All @@ -200,25 +203,29 @@ int main(int _argc, char ** _argv)
} else {
RCLCPP_ERROR(
ros2_node->get_logger(), "Failed to get XML from param [%s].", FLAGS_param.c_str());
rclcpp::shutdown();
return -1;
}
} else if (!FLAGS_string.empty()) { // string
req.set_sdf(FLAGS_string);
} else if (!FLAGS_topic.empty()) { // topic
// set XML string by fetching it from the given topic
if (!set_XML_from_topic(FLAGS_topic, ros2_node, req)) {
rclcpp::shutdown();
return -1;
}
} else {
RCLCPP_ERROR(
ros2_node->get_logger(), "Must specify either -file, -param, -string or -topic");
rclcpp::shutdown();
return -1;
}
// TODO(azeey) Deprecate use of command line flags in ROS 2 K-turtle in
// favor of ROS 2 parameters.
} else {
RCLCPP_ERROR(
ros2_node->get_logger(), "Must specify either file, string or topic as ROS 2 parameters");
rclcpp::shutdown();
return -1;
}

Expand Down

0 comments on commit aa68eb3

Please sign in to comment.