Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Ignore ros-args in parameter bridge #65

Merged
merged 3 commits into from
Mar 31, 2020
Merged
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
25 changes: 22 additions & 3 deletions ros_ign_bridge/src/parameter_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <list>
#include <memory>
#include <string>
#include <vector>

// Direction of bridge.
enum Direction
Expand Down Expand Up @@ -61,6 +62,24 @@ void usage()
".StringMsg" << std::endl;
}

//////////////////////////////////////////////////
std::vector<std::string> filter_args(int argc, char * argv[])
{
const std::string rosArgsBeginDelim = "--ros-args";
const std::string rosArgsEndDelim = "--";
// Skip first argument (executable path)
std::vector<std::string> args(argv + 1, argv + argc);
auto rosArgsPos = std::find(args.begin(), args.end(), rosArgsBeginDelim);
auto rosArgsEndPos = std::find(rosArgsPos, args.end(), rosArgsEndDelim);
// If -- was found, delete it as well
if (rosArgsEndPos != args.end())
++rosArgsEndPos;
// Delete args between --ros-args and -- (or --ros-args to end if not found)
if (rosArgsPos != args.end())
args.erase(rosArgsPos, rosArgsEndPos);
return args;
}

//////////////////////////////////////////////////
int main(int argc, char * argv[])
{
Expand All @@ -81,11 +100,11 @@ int main(int argc, char * argv[])
std::list<ros_ign_bridge::BridgeIgnToRosHandles> ign_to_ros_handles;
std::list<ros_ign_bridge::BridgeRosToIgnHandles> ros_to_ign_handles;

// Parse all arguments.
// Filter arguments (i.e. remove ros args) then parse all the remaining ones
const std::string delim = "@";
const size_t queue_size = 10;
for (auto i = 1; i < argc; ++i) {
std::string arg = std::string(argv[i]);
auto filteredArgs = filter_args(argc, argv);
for (auto& arg : filteredArgs) {
auto delimPos = arg.find(delim);
if (delimPos == std::string::npos || delimPos == 0) {
usage();
Expand Down