Skip to content

Commit

Permalink
feat: add record_option option
Browse files Browse the repository at this point in the history
  • Loading branch information
HansRobo committed Mar 6, 2025
1 parent 19732f3 commit f1411d7
Show file tree
Hide file tree
Showing 4 changed files with 63 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,8 @@ class Interpreter : public rclcpp_lifecycle::LifecycleNode,
String record_storage_id;
String record_option;
std::shared_ptr<OpenScenario> script;
std::list<std::shared_ptr<ScenarioDefinition>> scenarios;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,36 @@ auto start(Ts &&... xs) -> pid_t
}
}

inline auto start_with_vector(const std::vector<std::string>& args) -> pid_t
{
std::vector<std::string> command{
"python3", boost::algorithm::replace_all_copy(concealer::dollar("which ros2"), "\n", ""), "bag",
"record"};

command.insert(command.end(), args.begin(), args.end());

switch (process_id = fork()) {
case -1:
throw std::system_error(errno, std::system_category());

case 0:
#ifndef OPENSCENARIO_INTERPRETER_VERBOSE_RECORD
if (const auto fd = ::open("/dev/null", O_WRONLY)) {
::dup2(fd, STDOUT_FILENO);
::close(fd);
}
#endif
if (concealer::execute(command) < 0) {
std::cerr << std::system_error(errno, std::system_category()).what() << std::endl;
std::exit(EXIT_FAILURE);
}
return 0;

default:
return process_id;
}
}

auto stop() -> void;
} // namespace record
} // namespace openscenario_interpreter
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,8 @@ Interpreter::Interpreter(const rclcpp::NodeOptions & options)
output_directory("/tmp"),
publish_empty_context(false),
record(false),
record_storage_id("")
record_storage_id(""),
record_option("")
{
DECLARE_PARAMETER(local_frame_rate);
DECLARE_PARAMETER(local_real_time_factor);
Expand All @@ -58,6 +59,7 @@ Interpreter::Interpreter(const rclcpp::NodeOptions & options)
DECLARE_PARAMETER(publish_empty_context);
DECLARE_PARAMETER(record);
DECLARE_PARAMETER(record_storage_id);
DECLARE_PARAMETER(record_option);

declare_parameter<std::string>("speed_condition", "legacy");
SpeedCondition::compatibility =
Expand Down Expand Up @@ -120,6 +122,7 @@ auto Interpreter::on_configure(const rclcpp_lifecycle::State &) -> Result
GET_PARAMETER(publish_empty_context);
GET_PARAMETER(record);
GET_PARAMETER(record_storage_id);
GET_PARAMETER(record_option);

script = std::make_shared<OpenScenario>(osc_path);

Expand Down Expand Up @@ -260,16 +263,31 @@ auto Interpreter::on_activate(const rclcpp_lifecycle::State &) -> Result
},
[&]() {
if (record) {
if (record_storage_id == "") {
record::start(
"-a", "--exclude", "/sensing/camera/.*", "-o",
boost::filesystem::path(osc_path).replace_extension("").string());
} else {
record::start(
"-a", "--exclude", "/sensing/camera/.*", "-o",
boost::filesystem::path(osc_path).replace_extension("").string(), "-s",
record_storage_id);
std::vector<std::string> options;
options.push_back("-a");
options.push_back("--exclude");
options.push_back("/sensing/camera/.*");
options.push_back("-o");
options.push_back(boost::filesystem::path(osc_path).replace_extension("").string());
if (record_storage_id != "") {
options.push_back("-s");
options.push_back(record_storage_id);
}
if(record_option != ""){
auto split = [](const std::string& s)->std::vector<std::string> {
std::istringstream iss(s);
std::vector<std::string> result;
std::string token;

while (iss >> token) {
result.push_back(token);
}
return result;
};
auto splitted = split(record_option);
options.insert(options.end(), splitted.begin(), splitted.end());
}
record::start_with_vector(options);
}

SimulatorCore::activate(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,7 @@ def launch_setup(context, *args, **kwargs):
publish_empty_context = LaunchConfiguration("publish_empty_context", default=False)
record = LaunchConfiguration("record", default=True)
record_storage_id = LaunchConfiguration("record_storage_id", default="")
record_option = LaunchConfiguration("record_option", default="")
rviz_config = LaunchConfiguration("rviz_config", default=default_rviz_config_file())
scenario = LaunchConfiguration("scenario", default=Path("/dev/null"))
sensor_model = LaunchConfiguration("sensor_model", default="")
Expand Down Expand Up @@ -116,6 +117,7 @@ def launch_setup(context, *args, **kwargs):
print(f"publish_empty_context := {publish_empty_context.perform(context)}")
print(f"record := {record.perform(context)}")
print(f"record_storage_id := {record_storage_id.perform(context)}")
print(f"record_option := {record_option.perform(context)}")
print(f"rviz_config := {rviz_config.perform(context)}")
print(f"scenario := {scenario.perform(context)}")
print(f"sensor_model := {sensor_model.perform(context)}")
Expand Down Expand Up @@ -144,6 +146,7 @@ def make_parameters():
{"publish_empty_context" : publish_empty_context},
{"record": record},
{"record_storage_id": record_storage_id},
{"record_option": record_option},
{"rviz_config": rviz_config},
{"sensor_model": sensor_model},
{"sigterm_timeout": sigterm_timeout},
Expand Down

0 comments on commit f1411d7

Please sign in to comment.