int ms5525_airspeed_main(int argc, char *argv[]) { uint8_t i2c_bus = PX4_I2C_BUS_DEFAULT; int myoptind = 1; int ch; const char *myoptarg = nullptr; bool start_all = false; while ((ch = px4_getopt(argc, argv, "ab:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'b': i2c_bus = atoi(myoptarg); break; case 'a': start_all = true; break; default: ms5525_airspeed_usage(); return 0; } } if (myoptind >= argc) { ms5525_airspeed_usage(); return -1; } /* * Start/load the driver. */ if (!strcmp(argv[myoptind], "start")) { if (start_all) { return ms5525_airspeed::start(); } else { return ms5525_airspeed::start_bus(i2c_bus); } } /* * Stop the driver */ if (!strcmp(argv[myoptind], "stop")) { return ms5525_airspeed::stop(); } /* * Reset the driver. */ if (!strcmp(argv[myoptind], "reset")) { return ms5525_airspeed::reset(); } ms5525_airspeed_usage(); return 0; }
int reboot_main(int argc, char *argv[]) { int ch; bool to_bootloader = false; int myoptind = 1; const char *myoptarg = NULL; while ((ch = px4_getopt(argc, argv, "b", &myoptind, &myoptarg)) != -1) { switch (ch) { case 'b': to_bootloader = true; break; default: print_usage(); return 1; } } int ret = px4_shutdown_request(true, to_bootloader); if (ret < 0) { PX4_ERR("reboot failed (%i)", ret); return -1; } while (1) { usleep(1); } // this command should not return on success return 0; }
int sf1xx_main(int argc, char *argv[]) { // check for optional arguments int ch; int myoptind = 1; const char *myoptarg = nullptr; uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING; while ((ch = px4_getopt(argc, argv, "R:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'R': rotation = (uint8_t)atoi(myoptarg); PX4_INFO("Setting distance sensor orientation to %d", (int)rotation); break; default: PX4_WARN("Unknown option!"); } } /* * Start/load the driver. */ if (!strcmp(argv[myoptind], "start")) { sf1xx::start(rotation); } /* * Stop the driver */ if (!strcmp(argv[myoptind], "stop")) { sf1xx::stop(); } /* * Test the driver/device. */ if (!strcmp(argv[myoptind], "test")) { sf1xx::test(); } /* * Reset the driver. */ if (!strcmp(argv[myoptind], "reset")) { sf1xx::reset(); } /* * Print driver information. */ if (!strcmp(argv[myoptind], "info") || !strcmp(argv[myoptind], "status")) { sf1xx::info(); } PX4_ERR("unrecognized command, try 'start', 'test', 'reset' or 'info'"); return PX4_ERROR; }
int test_file2(int argc, char *argv[]) { int opt; uint16_t flags = 0; const char *filename = LOG_PATH "testfile2.dat"; uint32_t write_chunk = 64; uint32_t write_size = 5 * 1024; int myoptind = 1; const char *myoptarg = NULL; while ((opt = px4_getopt(argc, argv, "c:s:FLh", &myoptind, &myoptarg)) != EOF) { switch (opt) { case 'F': flags |= FLAG_FSYNC; break; case 'L': flags |= FLAG_LSEEK; break; case 's': write_size = strtoul(myoptarg, NULL, 0); break; case 'c': write_chunk = strtoul(myoptarg, NULL, 0); break; case 'h': default: usage(); return 1; } } argc -= myoptind; argv += myoptind; if (argc > 0) { filename = argv[0]; } /* check if microSD card is mounted */ struct stat buffer; if (stat(LOG_PATH, &buffer)) { fprintf(stderr, "no microSD card mounted, aborting file test"); return 1; } test_corruption(filename, write_chunk, write_size, flags); return 0; }
static int parse_options(int argc, char *argv[]) { int ch; int myoptind = 1; const char *myoptarg = nullptr; while ((ch = px4_getopt(argc, argv, "t:d:u:l:w:b:p:r:s:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 't': _options.transport = strcmp(myoptarg, "UDP") == 0 ? options::eTransports::UDP : options::eTransports::UART; break; case 'd': if (nullptr != myoptarg) strcpy(_options.device, myoptarg); break; case 'u': _options.update_time_ms = strtol(myoptarg, nullptr, 10); break; case 'l': _options.loops = strtol(myoptarg, nullptr, 10); break; case 'w': _options.sleep_ms = strtol(myoptarg, nullptr, 10); break; case 'b': _options.baudrate = strtoul(optarg, nullptr, 10); break; case 'p': _options.poll_ms = strtol(optarg, nullptr, 10); break; case 'r': _options.recv_port = strtoul(optarg, nullptr, 10); break; case 's': _options.send_port = strtoul(optarg, nullptr, 10); break; default: usage(argv[1]); return -1; } } if (_options.sleep_ms < 1) { _options.sleep_ms = 1; PX4_ERR("sleep time too low, using 1 ms"); } if (_options.poll_ms < 1) { _options.poll_ms = 1; PX4_ERR("poll timeout too low, using 1 ms"); } return 0; }
int reboot_main(int argc, char *argv[]) { int ch; bool to_bootloader = false; int myoptind = 1; const char *myoptarg = NULL; while ((ch = px4_getopt(argc, argv, "b", &myoptind, &myoptarg)) != -1) { switch (ch) { case 'b': to_bootloader = true; break; default: PX4_ERR("usage: reboot [-b]\n" " -b reboot into the bootloader"); } } px4_systemreset(to_bootloader); }
int fxas21002c_main(int argc, char *argv[]) { bool external_bus = false; int ch; enum Rotation rotation = ROTATION_NONE; int myoptind = 1; const char *myoptarg = NULL; while ((ch = px4_getopt(argc, argv, "XR:a:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'X': external_bus = true; break; case 'R': rotation = (enum Rotation)atoi(myoptarg); break; default: fxas21002c::usage(); exit(0); } } const char *verb = argv[myoptind]; /* * Start/load the driver. */ if (!strcmp(verb, "start")) { fxas21002c::start(external_bus, rotation); } /* * Test the driver/device. */ if (!strcmp(verb, "test")) { fxas21002c::test(); } /* * Reset the driver. */ if (!strcmp(verb, "reset")) { fxas21002c::reset(); } /* * Print driver information. */ if (!strcmp(verb, "info")) { fxas21002c::info(); } /* * dump device registers */ if (!strcmp(verb, "regdump")) { fxas21002c::regdump(); } /* * trigger an error */ if (!strcmp(verb, "testerror")) { fxas21002c::test_error(); } errx(1, "unrecognized command, try 'start', 'test', 'reset', 'info', 'testerror' or 'regdump'"); }
int esc_calib_main(int argc, char *argv[]) { const char *dev = PWM_OUTPUT0_DEVICE_PATH; char *ep; int ch; int ret; char c; unsigned max_channels = 0; uint32_t set_mask = 0; unsigned long channels; unsigned single_ch = 0; uint16_t pwm_high = PWM_DEFAULT_MAX; uint16_t pwm_low = PWM_DEFAULT_MIN; struct pollfd fds; fds.fd = 0; /* stdin */ fds.events = POLLIN; if (argc < 2) { usage("no channels provided"); return 1; } int arg_consumed = 0; int myoptind = 1; const char *myoptarg = NULL; while ((ch = px4_getopt(argc, argv, "d:c:m:al:h:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'd': dev = myoptarg; arg_consumed += 2; break; case 'c': /* Read in channels supplied as one int and convert to mask: 1234 -> 0xF */ channels = strtoul(myoptarg, &ep, 0); while ((single_ch = channels % 10)) { set_mask |= 1 << (single_ch - 1); channels /= 10; } break; case 'm': /* Read in mask directly */ set_mask = strtoul(myoptarg, &ep, 0); if (*ep != '\0') { usage("bad set_mask value"); return 1; } break; case 'a': /* Choose all channels */ for (unsigned i = 0; i < PWM_OUTPUT_MAX_CHANNELS; i++) { set_mask |= 1 << i; } break; case 'l': /* Read in custom low value */ pwm_low = strtoul(myoptarg, &ep, 0); if (*ep != '\0' #if PWM_LOWEST_MIN > 0 || pwm_low < PWM_LOWEST_MIN #endif || pwm_low > PWM_HIGHEST_MIN) { usage("low PWM invalid"); return 1; } break; case 'h': /* Read in custom high value */ pwm_high = strtoul(myoptarg, &ep, 0); if (*ep != '\0' || pwm_high > PWM_HIGHEST_MAX || pwm_high < PWM_LOWEST_MAX) { usage("high PWM invalid"); return 1; } break; default: usage(NULL); return 1; } } if (set_mask == 0) { usage("no channels chosen"); return 1; } if (pwm_low > pwm_high) { usage("low pwm is higher than high pwm"); return 1; } /* make sure no other source is publishing control values now */ struct actuator_controls_s actuators; int act_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); /* clear changed flag */ orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, act_sub, &actuators); /* wait 50 ms */ usleep(50000); /* now expect nothing changed on that topic */ bool orb_updated; orb_check(act_sub, &orb_updated); if (orb_updated) { PX4_ERR("ABORTING! Attitude control still active. Please ensure to shut down all controllers:\n" "\tmc_att_control stop\n" "\tfw_att_control stop\n"); return 1; } printf("\nATTENTION, please remove or fix propellers before starting calibration!\n" "\n" "Make sure\n" "\t - that the ESCs are not powered\n" "\t - that safety is off (two short blinks)\n" "\t - that the controllers are stopped\n" "\n" "Do you want to start calibration now: y or n?\n"); /* wait for user input */ while (1) { ret = poll(&fds, 1, 0); if (ret > 0) { if (read(0, &c, 1) <= 0) { printf("ESC calibration read error\n"); return 0; } if (c == 'y' || c == 'Y') { break; } else if (c == 0x03 || c == 0x63 || c == 'q') { printf("ESC calibration exited\n"); return 0; } else if (c == 'n' || c == 'N') { printf("ESC calibration aborted\n"); return 0; } else { printf("Unknown input, ESC calibration aborted\n"); return 0; } } /* rate limit to ~ 20 Hz */ usleep(50000); } /* open for ioctl only */ int fd = open(dev, 0); if (fd < 0) { PX4_ERR("can't open %s", dev); return 1; } /* get number of channels available on the device */ ret = ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&max_channels); if (ret != OK) { PX4_ERR("PWM_SERVO_GET_COUNT"); return 1; } /* tell IO/FMU that its ok to disable its safety with the switch */ ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0); if (ret != OK) { PX4_ERR("PWM_SERVO_SET_ARM_OK"); return 1; } /* tell IO/FMU that the system is armed (it will output values if safety is off) */ ret = ioctl(fd, PWM_SERVO_ARM, 0); if (ret != OK) { PX4_ERR("PWM_SERVO_ARM"); return 1; } printf("Outputs armed"); /* wait for user confirmation */ printf("\nHigh PWM set: %d\n" "\n" "Connect battery now and hit ENTER after the ESCs confirm the first calibration step\n" "\n", pwm_high); fflush(stdout); while (1) { /* set max PWM */ for (unsigned i = 0; i < max_channels; i++) { if (set_mask & 1 << i) { ret = ioctl(fd, PWM_SERVO_SET(i), pwm_high); if (ret != OK) { PX4_ERR("PWM_SERVO_SET(%d), value: %d", i, pwm_high); goto cleanup; } } } ret = poll(&fds, 1, 0); if (ret > 0) { if (read(0, &c, 1) <= 0) { printf("ESC calibration read error\n"); goto done; } if (c == 13) { break; } else if (c == 0x03 || c == 0x63 || c == 'q') { printf("ESC calibration exited"); goto done; } } /* rate limit to ~ 20 Hz */ usleep(50000); } printf("Low PWM set: %d\n" "\n" "Hit ENTER when finished\n" "\n", pwm_low); while (1) { /* set disarmed PWM */ for (unsigned i = 0; i < max_channels; i++) { if (set_mask & 1 << i) { ret = ioctl(fd, PWM_SERVO_SET(i), pwm_low); if (ret != OK) { PX4_ERR("PWM_SERVO_SET(%d), value: %d", i, pwm_low); goto cleanup; } } } ret = poll(&fds, 1, 0); if (ret > 0) { if (read(0, &c, 1) <= 0) { printf("ESC calibration read error\n"); goto done; } if (c == 13) { break; } else if (c == 0x03 || c == 0x63 || c == 'q') { printf("ESC calibration exited\n"); goto done; } } /* rate limit to ~ 20 Hz */ usleep(50000); } /* disarm */ ret = ioctl(fd, PWM_SERVO_DISARM, 0); if (ret != OK) { PX4_ERR("PWM_SERVO_DISARM"); goto cleanup; } printf("Outputs disarmed"); printf("ESC calibration finished\n"); done: close(fd); return 0; cleanup: close(fd); return 1; }
/** * Start the driver. */ int start(int argc, char *argv[]) { int fd; /* entry check: */ if (start_in_progress) { warnx("start already in progress"); return 1; } if (g_dev != nullptr) { start_in_progress = false; warnx("already started"); return 1; } /* parse command line options */ int address = I2C_FLOW_ADDRESS_DEFAULT; int conversion_interval = PX4FLOW_CONVERSION_INTERVAL_DEFAULT; /* don't exit from getopt loop to leave getopt global variables in consistent state, * set error flag instead */ bool err_flag = false; int ch; int myoptind = 1; const char *myoptarg = nullptr; uint8_t sonar_rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING; while ((ch = px4_getopt(argc, argv, "a:i:R:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'a': address = strtoul(myoptarg, nullptr, 16); if (address < I2C_FLOW_ADDRESS_MIN || address > I2C_FLOW_ADDRESS_MAX) { warnx("invalid i2c address '%s'", myoptarg); err_flag = true; } break; case 'i': conversion_interval = strtoul(myoptarg, nullptr, 10); if (conversion_interval < PX4FLOW_CONVERSION_INTERVAL_MIN || conversion_interval > PX4FLOW_CONVERSION_INTERVAL_MAX) { warnx("invalid conversion interval '%s'", myoptarg); err_flag = true; } break; case 'R': sonar_rotation = (uint8_t)atoi(myoptarg); PX4_INFO("Setting sonar orientation to %d", (int)sonar_rotation); break; default: err_flag = true; break; } } if (err_flag) { usage(); return PX4_ERROR; } /* starting */ start_in_progress = true; warnx("scanning I2C buses for device.."); int retry_nr = 0; while (1) { const int busses_to_try[] = { PX4_I2C_BUS_EXPANSION, #ifdef PX4_I2C_BUS_ESC PX4_I2C_BUS_ESC, #endif #ifdef PX4_I2C_BUS_ONBOARD PX4_I2C_BUS_ONBOARD, #endif -1 }; const int *cur_bus = busses_to_try; while (*cur_bus != -1) { /* create the driver */ /* warnx("trying bus %d", *cur_bus); */ g_dev = new PX4FLOW(*cur_bus, address, (enum Rotation)0, conversion_interval, sonar_rotation); if (g_dev == nullptr) { /* this is a fatal error */ break; } /* init the driver: */ if (OK == g_dev->init()) { /* success! */ break; } /* destroy it again because it failed. */ delete g_dev; g_dev = nullptr; /* try next! */ cur_bus++; } /* check whether we found it: */ if (*cur_bus != -1) { /* check for failure: */ if (g_dev == nullptr) { break; } /* set the poll rate to default, starts automatic data collection */ fd = open(PX4FLOW0_DEVICE_PATH, O_RDONLY); if (fd < 0) { break; } if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MAX) < 0) { break; } /* success! */ start_in_progress = false; return 0; } if (retry_nr < START_RETRY_COUNT) { /* lets not be too verbose */ // warnx("PX4FLOW not found on I2C busses. Retrying in %d ms. Giving up in %d retries.", START_RETRY_TIMEOUT, START_RETRY_COUNT - retry_nr); usleep(START_RETRY_TIMEOUT * 1000); retry_nr++; } else { break; } } if (g_dev != nullptr) { delete g_dev; g_dev = nullptr; } start_in_progress = false; return 1; }
int leddar_one_main(int argc, char *argv[]) { int ch; int myoptind = 1; const char *myoptarg = nullptr; const char *serial_port = "/dev/ttyS3"; uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING; static leddar_one *inst = nullptr; while ((ch = px4_getopt(argc, argv, "d:r", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'd': serial_port = myoptarg; break; case 'r': rotation = (uint8_t)atoi(myoptarg); break; default: help(); return PX4_ERROR; } } if (myoptind >= argc) { help(); return PX4_ERROR; } const char *verb = argv[myoptind]; if (!strcmp(verb, "start")) { inst = new leddar_one(DEVICE_PATH, serial_port, rotation); if (!inst) { PX4_ERR("No memory to allocate " NAME); return PX4_ERROR; } if (inst->init() != PX4_OK) { delete inst; return PX4_ERROR; } inst->start(); } else if (!strcmp(verb, "stop")) { delete inst; inst = nullptr; } else if (!strcmp(verb, "test")) { int fd = open(DEVICE_PATH, O_RDONLY); ssize_t sz; struct distance_sensor_s report; if (fd < 0) { PX4_ERR("Unable to open %s", DEVICE_PATH); return PX4_ERROR; } sz = read(fd, &report, sizeof(report)); close(fd); if (sz != sizeof(report)) { PX4_ERR("No sample available in %s", DEVICE_PATH); return PX4_ERROR; } print_message(report); } else { help(); return PX4_ERROR; } return PX4_OK; }
int ist8310_main(int argc, char *argv[]) { IST8310_BUS i2c_busid = IST8310_BUS_ALL; int i2c_addr = IST8310_BUS_I2C_ADDR; /* 7bit */ enum Rotation rotation = ROTATION_NONE; bool calibrate = false; int myoptind = 1; int ch; const char *myoptarg = nullptr; while ((ch = px4_getopt(argc, argv, "R:Ca:b:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'R': rotation = (enum Rotation)atoi(myoptarg); break; case 'a': i2c_addr = (int)strtol(myoptarg, NULL, 0); break; case 'b': i2c_busid = (IST8310_BUS)strtol(myoptarg, NULL, 0); break; case 'C': calibrate = true; break; default: ist8310::usage(); exit(0); } } if (myoptind >= argc) { ist8310::usage(); return 1; } const char *verb = argv[myoptind]; /* * Start/load the driver. */ if (!strcmp(verb, "start")) { ist8310::start(i2c_busid, i2c_addr, rotation); if (i2c_busid == IST8310_BUS_ALL) { PX4_ERR("calibration only feasible against one bus"); return 1; } else if (calibrate && (ist8310::calibrate(i2c_busid) != 0)) { PX4_ERR("calibration failed"); return 1; } return 0; } /* * Test the driver/device. */ if (!strcmp(verb, "test")) { ist8310::test(i2c_busid); } /* * Reset the driver. */ if (!strcmp(verb, "reset")) { ist8310::reset(i2c_busid); } /* * Print driver information. */ if (!strcmp(verb, "info") || !strcmp(verb, "status")) { ist8310::info(i2c_busid); } /* * Autocalibrate the scaling */ if (!strcmp(verb, "calibrate")) { if (ist8310::calibrate(i2c_busid) == 0) { PX4_INFO("calibration successful"); return 0; } else { PX4_ERR("calibration failed"); return 1; } } ist8310::usage(); return 1; }
int sf1xx_main(int argc, char *argv[]) { int ch; int myoptind = 1; const char *myoptarg = nullptr; uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING; bool start_all = false; int i2c_bus = SF1XX_BUS_DEFAULT; while ((ch = px4_getopt(argc, argv, "ab:R:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'R': rotation = (uint8_t)atoi(myoptarg); break; case 'b': i2c_bus = atoi(myoptarg); break; case 'a': start_all = true; break; default: PX4_WARN("Unknown option!"); goto out_error; } } if (myoptind >= argc) { goto out_error; } /* * Start/load the driver. */ if (!strcmp(argv[myoptind], "start")) { if (start_all) { return sf1xx::start(rotation); } else { return sf1xx::start_bus(rotation, i2c_bus); } } /* * Stop the driver */ if (!strcmp(argv[myoptind], "stop")) { return sf1xx::stop(); } /* * Test the driver/device. */ if (!strcmp(argv[myoptind], "test")) { return sf1xx::test(); } /* * Reset the driver. */ if (!strcmp(argv[myoptind], "reset")) { return sf1xx::reset(); } /* * Print driver information. */ if (!strcmp(argv[myoptind], "info") || !strcmp(argv[myoptind], "status")) { return sf1xx::info(); } out_error: sf1xx_usage(); return PX4_ERROR; }
int ll40ls_main(int argc, char *argv[]) { int ch; int myoptind = 1; const char *myoptarg = nullptr; enum LL40LS_BUS busid = LL40LS_BUS_I2C_ALL; uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING; while ((ch = px4_getopt(argc, argv, "IXR:", &myoptind, &myoptarg)) != EOF) { switch (ch) { #ifdef PX4_I2C_BUS_ONBOARD case 'I': busid = LL40LS_BUS_I2C_INTERNAL; break; #endif case 'X': busid = LL40LS_BUS_I2C_EXTERNAL; break; case 'R': rotation = (uint8_t)atoi(myoptarg); PX4_INFO("Setting Lidar orientation to %d", (int)rotation); break; default: ll40ls::usage(); return 0; } } /* Determine protocol first because it's needed next. */ if (argc > myoptind + 1) { const char *protocol = argv[myoptind + 1]; if (!strcmp(protocol, "pwm")) { busid = LL40LS_BUS_PWM;; } else if (!strcmp(protocol, "i2c")) { // Do nothing } else { warnx("unknown protocol, choose pwm or i2c"); ll40ls::usage(); return 0; } } /* Now determine action. */ if (argc > myoptind) { const char *verb = argv[myoptind]; if (!strcmp(verb, "start")) { ll40ls::start(busid, rotation); } else if (!strcmp(verb, "stop")) { ll40ls::stop(); } else if (!strcmp(verb, "test")) { ll40ls::test(); } else if (!strcmp(verb, "reset")) { ll40ls::reset(); } else if (!strcmp(verb, "regdump")) { ll40ls::regdump(); } else if (!strcmp(verb, "info") || !strcmp(verb, "status")) { ll40ls::info(); } else { ll40ls::usage(); } return 0; } warnx("unrecognized command, try 'start', 'test', 'reset', 'info' or 'regdump'"); ll40ls::usage(); return 0; }
int tfmini_main(int argc, char *argv[]) { int ch; uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING; const char *device_path = ""; int myoptind = 1; const char *myoptarg = nullptr; while ((ch = px4_getopt(argc, argv, "R:d:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'R': rotation = (uint8_t)atoi(myoptarg); break; case 'd': device_path = myoptarg; break; default: PX4_WARN("Unknown option!"); return -1; } } if (myoptind >= argc) { goto out_error; } /* * Start/load the driver. */ if (!strcmp(argv[myoptind], "start")) { if (strcmp(device_path, "") != 0) { tfmini::start(device_path, rotation); } else { PX4_WARN("Please specify device path!"); tfmini::usage(); return -1; } } /* * Stop the driver */ if (!strcmp(argv[myoptind], "stop")) { tfmini::stop(); } /* * Test the driver/device. */ if (!strcmp(argv[myoptind], "test")) { tfmini::test(); } /* * Reset the driver. */ if (!strcmp(argv[myoptind], "reset")) { tfmini::reset(); } /* * Print driver information. */ if (!strcmp(argv[myoptind], "info") || !strcmp(argv[myoptind], "status")) { tfmini::info(); } out_error: PX4_ERR("unrecognized command, try 'start', 'test', 'reset' or 'info'"); return -1; }
int bmi055_main(int argc, char *argv[]) { bool external_bus = false; int ch; enum Rotation rotation = ROTATION_NONE; enum sensor_type sensor = BMI055_NONE; int myoptind = 1; const char *myoptarg = NULL; /* jump over start/off/etc and look at options first */ while ((ch = px4_getopt(argc, argv, "XR:AG", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'X': external_bus = true; break; case 'R': rotation = (enum Rotation)atoi(myoptarg); break; case 'A': sensor = BMI055_ACCEL; break; case 'G': sensor = BMI055_GYRO; break; default: bmi055::usage(); exit(0); } } const char *verb = argv[myoptind]; if (sensor == BMI055_NONE) { bmi055::usage(); exit(0); } /* * Start/load the driver. */ if (!strcmp(verb, "start")) { bmi055::start(external_bus, rotation, sensor); } /* * Stop the driver. */ if (!strcmp(verb, "stop")) { bmi055::stop(external_bus, sensor); } /* * Test the driver/device. */ if (!strcmp(verb, "test")) { bmi055::test(external_bus, sensor); } /* * Reset the driver. */ if (!strcmp(verb, "reset")) { bmi055::reset(external_bus, sensor); } /* * Print driver information. */ if (!strcmp(verb, "info")) { bmi055::info(external_bus, sensor); } /* * Print register information. */ if (!strcmp(verb, "regdump")) { bmi055::regdump(external_bus, sensor); } if (!strcmp(verb, "testerror")) { bmi055::testerror(external_bus, sensor); } bmi055::usage(); exit(1); }
int l3gd20_main(int argc, char *argv[]) { int myoptind = 1; int ch; const char *myoptarg = nullptr; bool external_bus = false; enum Rotation rotation = ROTATION_NONE; while ((ch = px4_getopt(argc, argv, "XR:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'X': external_bus = true; break; case 'R': rotation = (enum Rotation)atoi(myoptarg); break; default: l3gd20::usage(); return 0; } } if (myoptind >= argc) { l3gd20::usage(); return -1; } const char *verb = argv[myoptind]; /* * Start/load the driver. */ if (!strcmp(verb, "start")) { l3gd20::start(external_bus, rotation); } /* * Test the driver/device. */ if (!strcmp(verb, "test")) { l3gd20::test(); } /* * Reset the driver. */ if (!strcmp(verb, "reset")) { l3gd20::reset(); } /* * Print driver information. */ if (!strcmp(verb, "info")) { l3gd20::info(); } /* * Print register information. */ if (!strcmp(verb, "regdump")) { l3gd20::regdump(); } /* * trigger an error */ if (!strcmp(verb, "testerror")) { l3gd20::test_error(); } PX4_ERR("unrecognized command, try 'start', 'test', 'reset', 'info', 'testerror' or 'regdump'"); return -1; }
int navio_sysfs_pwm_out_main(int argc, char *argv[]) { const char *device = nullptr; int ch; int myoptind = 1; const char *myoptarg = nullptr; char *verb = nullptr; if (argc >= 2) { verb = argv[1]; } else { return 1; } while ((ch = px4_getopt(argc, argv, "d:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'd': device = myoptarg; strncpy(navio_sysfs_pwm_out::_device, device, strlen(device)); break; } } // gets the parameters for the esc's pwm param_get(param_find("PWM_DISARMED"), &navio_sysfs_pwm_out::_pwm_disarmed); param_get(param_find("PWM_MIN"), &navio_sysfs_pwm_out::_pwm_min); param_get(param_find("PWM_MAX"), &navio_sysfs_pwm_out::_pwm_max); /* * Start/load the driver. */ if (!strcmp(verb, "start")) { if (navio_sysfs_pwm_out::_is_running) { PX4_WARN("pwm_out already running"); return 1; } navio_sysfs_pwm_out::start(); } else if (!strcmp(verb, "stop")) { if (!navio_sysfs_pwm_out::_is_running) { PX4_WARN("pwm_out is not running"); return 1; } navio_sysfs_pwm_out::stop(); } else if (!strcmp(verb, "status")) { PX4_WARN("pwm_out is %s", navio_sysfs_pwm_out::_is_running ? "running" : "not running"); return 0; } else { navio_sysfs_pwm_out::usage(); return 1; } return 0; }
int tap_esc_main(int argc, char *argv[]) { const char *device = nullptr; int ch; int myoptind = 1; const char *myoptarg = nullptr; char *verb = nullptr; if (argc >= 2) { verb = argv[1]; } while ((ch = px4_getopt(argc, argv, "d:n:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'd': device = myoptarg; strncpy(tap_esc_drv::_device, device, strlen(device)); break; case 'n': tap_esc_drv::_supported_channel_count = atoi(myoptarg); break; } } if (!tap_esc && tap_esc_drv::_task_handle != -1) { tap_esc_drv::_task_handle = -1; } // Start/load the driver. if (!strcmp(verb, "start")) { if (tap_esc_drv::_is_running) { PX4_WARN("tap_esc already running"); return 1; } // Check on required arguments if (tap_esc_drv::_supported_channel_count == 0 || device == nullptr || strlen(device) == 0) { tap_esc_drv::usage(); return 1; } tap_esc_drv::start(); } else if (!strcmp(verb, "stop")) { if (!tap_esc_drv::_is_running) { PX4_WARN("tap_esc is not running"); return 1; } tap_esc_drv::stop(); } else if (!strcmp(verb, "status")) { PX4_WARN("tap_esc is %s", tap_esc_drv::_is_running ? "running" : "not running"); return 0; } else { tap_esc_drv::usage(); return 1; } return 0; }
int pmw3901_main(int argc, char *argv[]) { if (argc < 2) { pmw3901::usage(); return PX4_ERROR; } // don't exit from getopt loop to leave getopt global variables in consistent state, // set error flag instead bool err_flag = false; int ch; int myoptind = 1; const char *myoptarg = nullptr; int spi_bus = PMW3901_BUS; while ((ch = px4_getopt(argc, argv, "b:", &myoptind, &myoptarg)) != EOF) { switch (ch) { case 'b': spi_bus = (uint8_t)atoi(myoptarg); break; default: err_flag = true; break; } } if (err_flag) { pmw3901::usage(); return PX4_ERROR; } /* * Start/load the driver. */ if (!strcmp(argv[myoptind], "start")) { pmw3901::start(spi_bus); } /* * Stop the driver */ if (!strcmp(argv[myoptind], "stop")) { pmw3901::stop(); } /* * Test the driver/device. */ if (!strcmp(argv[myoptind], "test")) { pmw3901::test(); } /* * Print driver information. */ if (!strcmp(argv[myoptind], "info") || !strcmp(argv[myoptind], "status")) { pmw3901::info(); } pmw3901::usage(); return PX4_ERROR; }