Skip to content

Commit

Permalink
Clean and improve helper messages
Browse files Browse the repository at this point in the history
  • Loading branch information
fspindle committed Dec 2, 2024
1 parent 6773825 commit 55e401a
Show file tree
Hide file tree
Showing 3 changed files with 104 additions and 36 deletions.
23 changes: 1 addition & 22 deletions example/servo-franka/frankaGripper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,6 @@ int main(int argc, char **argv)
double opt_grasping_width = 0.;
double opt_grasping_speed = 0.1;
double opt_grasping_force = 60;
double opt_grasping_time = 0;
GripperState_t opt_gripper_state = Gripper_None;

for (int i = 1; i < argc; i++) {
Expand Down Expand Up @@ -97,10 +96,6 @@ int main(int argc, char **argv)
++i;
opt_grasping_force = std::atof(argv[i]);
}
else if (std::string(argv[i]) == "--grasp-time" && i + 1 < argc) {
++i;
opt_grasping_time = std::atof(argv[i]);
}
else if (std::string(argv[i]) == "--test" && i + 1 < argc) {
++i;
opt_gripper_state = Gripper_Test;
Expand All @@ -109,14 +104,13 @@ int main(int argc, char **argv)
else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
std::cout << "SYNOPSYS" << std::endl
<< " " << argv[0]
<< " [--ip <default " << opt_robot_ip << ">]"
<< " [--ip <controller ip>]"
<< " [--home]"
<< " [--open]"
<< " [--close]"
<< " [--grasp <width>]"
<< " [--grasp-speed <speed>]"
<< " [--grasp-force <force>]"
<< " [--grasp-time <duration>]"
<< " [--release]"
<< " [--test <width>]"
<< " [--help] [-h]\n" << std::endl;
Expand Down Expand Up @@ -149,11 +143,6 @@ int main(int argc, char **argv)
<< " Force in [N] applied during grasping." << std::endl
<< " Default: " << opt_grasping_force << " [N]" << std::endl
<< std::endl
<< " --grasp-time <duration>" << std::endl
<< " Duration in [s] the grasping force will be applied before releasing the object." << std::endl
<< " When duration is set to -1, grasping will be applied until stopped by CTRL-C." << std::endl
<< " Default: " << opt_grasping_time << " [s]" << std::endl
<< std::endl
<< " --release" << std::endl
<< " Release an object that is grasped." << std::endl
<< std::endl
Expand Down Expand Up @@ -205,16 +194,6 @@ int main(int argc, char **argv)
else if (opt_gripper_state == Gripper_Grasp) {
std::cout << "Gripper grasp " << opt_grasping_width << "m object width, with speed: " << opt_grasping_speed << " and force: " << opt_grasping_force << "N..." << std::endl;
robot.gripperGrasp(opt_grasping_width, opt_grasping_speed, opt_grasping_force);
if (opt_grasping_time < 0) {
std::cout << "Hit CTRL-C to quit. The grasping force will continue to be applied..." << std::endl;
while (1) {
vpTime::sleepMs(1000);
}
}
else {
std::cout << "Wait " << 1000 * opt_grasping_time << " seconds before releasing the object" << std::endl;
vpTime::sleepMs(1000 * opt_grasping_time);
}
}
else if (opt_gripper_state == Gripper_Release) {
std::cout << "Gripper release object..." << std::endl;
Expand Down
63 changes: 54 additions & 9 deletions example/servo-franka/servoFrankaIBVS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ int main(int argc, char **argv)
double convergence_threshold = 0.00005;

for (int i = 1; i < argc; i++) {
if ((std::string(argv[i]) == "--tag_size") && (i + 1 < argc)) {
if ((std::string(argv[i]) == "--tag-size") && (i + 1 < argc)) {
opt_tagSize = std::stod(argv[i + 1]);
++i;
}
Expand All @@ -134,26 +134,71 @@ int main(int argc, char **argv)
else if (std::string(argv[i]) == "--plot") {
opt_plot = true;
}
else if (std::string(argv[i]) == "--adaptive_gain") {
else if (std::string(argv[i]) == "--adaptive-gain") {
opt_adaptive_gain = true;
}
else if (std::string(argv[i]) == "--task_sequencing") {
else if (std::string(argv[i]) == "--task-sequencing") {
opt_task_sequencing = true;
}
else if ((std::string(argv[i]) == "--quad_decimate") && (i + 1 < argc)) {
else if ((std::string(argv[i]) == "--quad-decimate") && (i + 1 < argc)) {
opt_quad_decimate = std::stoi(argv[i + 1]);
++i;
}
else if (std::string(argv[i]) == "--no-convergence-threshold") {
convergence_threshold = 0.;
}
else if ((std::string(argv[i]) == "--help") || (std::string(argv[i]) == "-h")) {
std::cout
<< argv[0] << " [--ip <default " << opt_robot_ip << ">] [--tag_size <marker size in meter; default "
<< opt_tagSize << ">] [--eMc <eMc extrinsic file>] "
<< "[--quad_decimate <decimation; default " << opt_quad_decimate
<< ">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
std::cout << "SYNOPSYS" << std::endl
<< " " << argv[0]
<< " [--ip <controller ip>]"
<< " [--tag-size <size>]"
<< " [--eMc <extrinsic transformation file>]"
<< " [--quad-decimate <decimation factor>]"
<< " [--adaptive-gain]"
<< " [--plot]"
<< " [--task-sequencing]"
<< " [--no-convergence-threshold]"
<< " [--verbose]"
<< " [--help] [-h]\n"
<< std::endl;
std::cout << "DESCRIPTION" << std::endl
<< " Use an image-based visual-servoing scheme to position the camera in front of an Apriltag." << std::endl
<< std::endl
<< " --ip <controller ip>" << std::endl
<< " Franka controller ip address" << std::endl
<< " Default: " << opt_robot_ip << std::endl
<< std::endl
<< " --tag-size <size>" << std::endl
<< " Apriltag size in [m]." << std::endl
<< " Default: " << opt_tagSize << " [m]" << std::endl
<< std::endl
<< " --eMc <extrinsic transformation file>" << std::endl
<< " File containing the homogeneous transformation matrix between" << std::endl
<< " robot end-effector and camera frame." << std::endl
<< std::endl
<< " --quad-decimate <decimation factor>" << std::endl
<< " Decimation factor used during Apriltag detection." << std::endl
<< " Default: " << opt_quad_decimate << std::endl
<< std::endl
<< " --adaptive-gain" << std::endl
<< " Flag to enable adaptive gain to speed up visual servo near convergence." << std::endl
<< std::endl
<< " --plot" << std::endl
<< " Flag to enable curve plotter." << std::endl
<< std::endl
<< " --task-sequencing" << std::endl
<< " Flag to enable task sequencing scheme." << std::endl
<< std::endl
<< " --no-convergence-threshold" << std::endl
<< " Flag to disable convergence threshold used to stop the visual servo." << std::endl
<< std::endl
<< " --verbose" << std::endl
<< " Flag to enable extra verbosity." << std::endl
<< std::endl
<< " --help, -h" << std::endl
<< " Print this helper message." << std::endl
<< std::endl;

return EXIT_SUCCESS;
}
}
Expand Down
54 changes: 49 additions & 5 deletions example/servo-franka/servoFrankaPBVS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,11 +147,55 @@ int main(int argc, char **argv)
convergence_threshold_tu = 0.;
}
else if ((std::string(argv[i]) == "--help") || (std::string(argv[i]) == "-h")) {
std::cout
<< argv[0] << " [--ip <default " << opt_robot_ip << ">] [--tag_size <marker size in meter; default "
<< opt_tagSize << ">] [--eMc <eMc extrinsic file>] "
<< "[--quad_decimate <decimation; default " << opt_quad_decimate
<< ">] [--adaptive_gain] [--plot] [--task_sequencing] [--no-convergence-threshold] [--verbose] [--help] [-h]"
std::cout << "SYNOPSYS" << std::endl
<< " " << argv[0]
<< " [--ip <controller ip>]"
<< " [--tag-size <size>]"
<< " [--eMc <extrinsic transformation file>]"
<< " [--quad-decimate <decimation factor>]"
<< " [--adaptive-gain]"
<< " [--plot]"
<< " [--task-sequencing]"
<< " [--no-convergence-threshold]"
<< " [--verbose]"
<< " [--help] [-h]\n"
<< std::endl;
std::cout << "DESCRIPTION" << std::endl
<< " Use a position-based visual-servoing scheme to position the camera in front of an Apriltag." << std::endl
<< std::endl
<< " --ip <controller ip>" << std::endl
<< " Franka controller ip address" << std::endl
<< " Default: " << opt_robot_ip << std::endl
<< std::endl
<< " --tag-size <size>" << std::endl
<< " Apriltag size in [m]." << std::endl
<< " Default: " << opt_tagSize << " [m]" << std::endl
<< std::endl
<< " --eMc <extrinsic transformation file>" << std::endl
<< " File containing the homogeneous transformation matrix between" << std::endl
<< " robot end-effector and camera frame." << std::endl
<< std::endl
<< " --quad-decimate <decimation factor>" << std::endl
<< " Decimation factor used during Apriltag detection." << std::endl
<< " Default: " << opt_quad_decimate << std::endl
<< std::endl
<< " --adaptive-gain" << std::endl
<< " Flag to enable adaptive gain to speed up visual servo near convergence." << std::endl
<< std::endl
<< " --plot" << std::endl
<< " Flag to enable curve plotter." << std::endl
<< std::endl
<< " --task-sequencing" << std::endl
<< " Flag to enable task sequencing scheme." << std::endl
<< std::endl
<< " --no-convergence-threshold" << std::endl
<< " Flag to disable convergence threshold used to stop the visual servo." << std::endl
<< std::endl
<< " --verbose" << std::endl
<< " Flag to enable extra verbosity." << std::endl
<< std::endl
<< " --help, -h" << std::endl
<< " Print this helper message." << std::endl
<< std::endl;
return EXIT_SUCCESS;
}
Expand Down

0 comments on commit 55e401a

Please sign in to comment.