Skip to content

Commit

Permalink
refactor: get port_name and type from argv
Browse files Browse the repository at this point in the history
  • Loading branch information
FaaizHaikal committed Mar 3, 2024
1 parent 22ba151 commit 33a4d51
Showing 1 changed file with 48 additions and 10 deletions.
58 changes: 48 additions & 10 deletions src/kansei_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,29 +35,67 @@ int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);

std::string port_name = "/dev/ttyUSB1";
std::string port_name = "/dev/ttyUSB0";
std::string fallen_type = "";
std::string path = "";

const char * help_message =
"Usage: ros2 run kansei main --path [config_path] --type [fallen_type]\n"
"[config_path]: path to the configuration file\n"
"[fallen_type]: fallen type to be used (orientation / accelero)\n"
"Optional:\n"
"-h, --help show this help message and exit\n";

if (argc > 1) {
port_name = argv[1];
for (int i = 1; i < argc; i++) {
std::string arg = argv[i];
if (arg == "-h" || arg == "--help") {
std::cout << help_message << std::endl;
return 1;
} else if (arg == "--path") {
if (i + 1 < argc) {
path = argv[i + 1];
i++;
} else {
std::cerr << "Error: --path requires a path argument" << std::endl;
return 1;
}
} else if (arg == "--type") {
if (i + 1 < argc) {
fallen_type = argv[i + 1];
i++;
} else {
std::cerr << "Error: --type requires a fallen type argument" << std::endl;
return 1;
}
}
}
} else {
std::cout << "Invalid arguments!\n\n" << help_message << "\n";
return 0;
}

std::cout << "set the port name as " << port_name << "\n";
auto mpu = std::make_shared<kansei::measurement::MPU>(port_name);

std::cout << "connect to mpu\n";
if (mpu->connect()) {
std::cout << "succeeded to connect to mpu!\n";
std::cout << "succeeded to connect to mpu " << port_name << "!\n";
} else {
std::cout << "failed to connect to mpu!\n" <<
"try again!\n";
return 0;
port_name = "/dev/ttyUSB1";
mpu->set_port_name(port_name);
if (mpu->connect()) {
std::cout << "succeeded to connect to mpu " << port_name << "!\n";
} else {
std::cout << "failed to connect to mpu!\n" <<
"try again!\n";
return 0;
}
}

auto node = std::make_shared<rclcpp::Node>("kansei_node");
auto kansei_node = std::make_shared<kansei::KanseiNode>(node);

auto fallen = std::make_shared<kansei::fallen::FallenDeterminant>(
kansei::fallen::DeterminantType::ACCELERO);
auto fallen = std::make_shared<kansei::fallen::FallenDeterminant>(fallen_type);
fallen->load_config(path);

kansei_node->set_measurement_unit(mpu);
kansei_node->set_fallen_determinant(fallen);
Expand Down

0 comments on commit 33a4d51

Please sign in to comment.