Skip to content

Commit 2971f2f

Browse files
committed
merge the remapping argument into Player's NodeOption.
Signed-off-by: Tomoya Fujita <[email protected]>
1 parent 9002ec2 commit 2971f2f

File tree

1 file changed

+35
-4
lines changed

1 file changed

+35
-4
lines changed

rosbag2_transport/src/rosbag2_transport/player.cpp

Lines changed: 35 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -2167,7 +2167,17 @@ Player::Player(
21672167
const rclcpp::NodeOptions & node_options)
21682168
: rclcpp::Node(
21692169
node_name,
2170-
rclcpp::NodeOptions(node_options).arguments(play_options.topic_remapping_options))
2170+
// Merge existing arguments with topic remapping options
2171+
rclcpp::NodeOptions(node_options).arguments(
2172+
[&, node_options]() {
2173+
auto args = node_options.arguments();
2174+
args.insert(args.end(),
2175+
play_options.topic_remapping_options.begin(),
2176+
play_options.topic_remapping_options.end());
2177+
return args;
2178+
}()
2179+
)
2180+
)
21712181
{
21722182
std::shared_ptr<KeyboardHandler> keyboard_handler;
21732183
if (!play_options.disable_keyboard_controls) {
@@ -2202,7 +2212,17 @@ Player::Player(
22022212
const rclcpp::NodeOptions & node_options)
22032213
: rclcpp::Node(
22042214
node_name,
2205-
rclcpp::NodeOptions(node_options).arguments(play_options.topic_remapping_options))
2215+
// Merge existing arguments with topic remapping options
2216+
rclcpp::NodeOptions(node_options).arguments(
2217+
[&, node_options]() {
2218+
auto args = node_options.arguments();
2219+
args.insert(args.end(),
2220+
play_options.topic_remapping_options.begin(),
2221+
play_options.topic_remapping_options.end());
2222+
return args;
2223+
}()
2224+
)
2225+
)
22062226
{
22072227
std::vector<reader_storage_options_pair_t> readers_with_options{};
22082228
readers_with_options.emplace_back(std::move(reader), storage_options);
@@ -2231,10 +2251,21 @@ Player::Player(
22312251
const rclcpp::NodeOptions & node_options)
22322252
: rclcpp::Node(
22332253
node_name,
2234-
rclcpp::NodeOptions(node_options).arguments(play_options.topic_remapping_options)),
2254+
// Merge existing arguments with topic remapping options
2255+
rclcpp::NodeOptions(node_options).arguments(
2256+
[&, node_options]() {
2257+
auto args = node_options.arguments();
2258+
args.insert(args.end(),
2259+
play_options.topic_remapping_options.begin(),
2260+
play_options.topic_remapping_options.end());
2261+
return args;
2262+
}()
2263+
)
2264+
),
22352265
pimpl_(std::make_unique<PlayerImpl>(
22362266
this, std::move(readers_with_options), std::move(keyboard_handler), play_options))
2237-
{}
2267+
{
2268+
}
22382269

22392270
Player::~Player() = default;
22402271

0 commit comments

Comments
 (0)