diff --git a/uwsim/interface_examples/gotoAbsolutePose.cpp b/uwsim/interface_examples/gotoAbsolutePose.cpp index 347c83c9..8fc06cc2 100644 --- a/uwsim/interface_examples/gotoAbsolutePose.cpp +++ b/uwsim/interface_examples/gotoAbsolutePose.cpp @@ -44,7 +44,7 @@ void vehiclePoseCallback(const nav_msgs::Odometry& odom) { int main(int argc, char **argv) { - if (argc!=9) { + if (argc < 9) { std::cerr << "USAGE: " << argv[0] << " " << std::endl; std::cerr << "units are meters and radians." << std::endl; return 0; diff --git a/uwsim/interface_examples/gotoRelativePose.cpp b/uwsim/interface_examples/gotoRelativePose.cpp index e2fcee20..9920c030 100644 --- a/uwsim/interface_examples/gotoRelativePose.cpp +++ b/uwsim/interface_examples/gotoRelativePose.cpp @@ -60,7 +60,7 @@ int main(int argc, char **argv) { ros::init(argc, argv, "gotoRelativePose"); ros::NodeHandle nh; - if (argc!=9) { + if (argc < 9) { std::cerr << "USAGE: " << argv[0] << " " << std::endl; std::cerr << "units are meters and radians." << std::endl; return 0; diff --git a/uwsim/interface_examples/makeVehicleSurvey.cpp b/uwsim/interface_examples/makeVehicleSurvey.cpp index 682fe6c9..61400b5a 100644 --- a/uwsim/interface_examples/makeVehicleSurvey.cpp +++ b/uwsim/interface_examples/makeVehicleSurvey.cpp @@ -23,7 +23,7 @@ int main(int argc, char **argv) { - if (argc!=8) { + if (argc < 8) { std::cerr << "USAGE: " << argv[0] << " " << std::endl; std::cerr << "units in meters and radians" << std::endl; return 0; diff --git a/uwsim/interface_examples/setJointPosition.cpp b/uwsim/interface_examples/setJointPosition.cpp index 6e7385ad..8fa6695b 100644 --- a/uwsim/interface_examples/setJointPosition.cpp +++ b/uwsim/interface_examples/setJointPosition.cpp @@ -15,7 +15,7 @@ #include int main(int argc, char **argv) { - if (argc != 7) { + if (argc < 7) { std::cerr << "Usage: " << argv[0] << " " << std::endl; std::cerr << "Units are radians" << std::endl; exit(0); diff --git a/uwsim/interface_examples/setJointVelocity.cpp b/uwsim/interface_examples/setJointVelocity.cpp index 71aab84f..02a17db9 100644 --- a/uwsim/interface_examples/setJointVelocity.cpp +++ b/uwsim/interface_examples/setJointVelocity.cpp @@ -15,7 +15,7 @@ #include int main(int argc, char **argv) { - if (argc != 7) { + if (argc < 7) { std::cerr << "Usage: " << argv[0] << " " << std::endl; std::cerr << "Units are radians/simulated_time. Time scale to be implemented." << std::endl; exit(0); diff --git a/uwsim/interface_examples/setVehicleDisturbances.cpp b/uwsim/interface_examples/setVehicleDisturbances.cpp index 94ee79e6..fb821eef 100644 --- a/uwsim/interface_examples/setVehicleDisturbances.cpp +++ b/uwsim/interface_examples/setVehicleDisturbances.cpp @@ -38,7 +38,7 @@ void vehiclePoseCallback(const nav_msgs::Odometry& odom) { int main(int argc, char **argv) { - if (argc!=9) { + if (argc < 9) { std::cerr << "USAGE: " << argv[0] << " " << std::endl; std::cerr << " is the maximum desired variation on the vehicle pose" << std::endl; std::cerr << "units in meters and radians" << std::endl; diff --git a/uwsim/interface_examples/setVehiclePose.cpp b/uwsim/interface_examples/setVehiclePose.cpp index df69d69c..21f42c8e 100644 --- a/uwsim/interface_examples/setVehiclePose.cpp +++ b/uwsim/interface_examples/setVehiclePose.cpp @@ -26,7 +26,7 @@ int main(int argc, char **argv) { ros::init(argc, argv, "setVehiclePose"); ros::NodeHandle nh; - if (argc!=8) { + if (argc < 8) { std::cerr << "USAGE: " << argv[0] << " " << std::endl; std::cerr << "units are in meters and radians." << std::endl; return 0; diff --git a/uwsim/interface_examples/setVehiclePosition.cpp b/uwsim/interface_examples/setVehiclePosition.cpp index fee4a0c3..2be7cf9e 100644 --- a/uwsim/interface_examples/setVehiclePosition.cpp +++ b/uwsim/interface_examples/setVehiclePosition.cpp @@ -25,7 +25,7 @@ int main(int argc, char **argv) { ros::init(argc, argv, "setVehiclePosition"); ros::NodeHandle nh; - if (argc!=8) { + if (argc < 8) { std::cerr << "USAGE: " << argv[0] << " " << std::endl; std::cerr << "units in meters and radians" << std::endl; return 0; diff --git a/uwsim/interface_examples/setVehicleTwist.cpp b/uwsim/interface_examples/setVehicleTwist.cpp index c42e3a25..72714187 100644 --- a/uwsim/interface_examples/setVehicleTwist.cpp +++ b/uwsim/interface_examples/setVehicleTwist.cpp @@ -21,7 +21,7 @@ int main(int argc, char **argv) { - if (argc!=8) { + if (argc < 8) { std::cerr << "USAGE: " << argv[0] << " " << std::endl; std::cerr << "units are displacement/simulated_time. Time scale to be implemented." << std::endl; return 0; diff --git a/uwsim/interface_examples/setVehicleVelocity.cpp b/uwsim/interface_examples/setVehicleVelocity.cpp index 6d148f73..94583f8a 100644 --- a/uwsim/interface_examples/setVehicleVelocity.cpp +++ b/uwsim/interface_examples/setVehicleVelocity.cpp @@ -21,7 +21,7 @@ int main(int argc, char **argv) { - if (argc!=8) { + if (argc < 8) { std::cerr << "USAGE: " << argv[0] << " " << std::endl; std::cerr << "units are displacement/simulated_time. Time scale to be implemented." << std::endl; return 0;