diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp index b4570e4bbd..316e88bc59 100644 --- a/src/drivers/airspeed/airspeed.cpp +++ b/src/drivers/airspeed/airspeed.cpp @@ -86,8 +86,8 @@ Airspeed::Airspeed(int bus, int address, unsigned conversion_interval, const cha _measure_ticks(0), _collect_phase(false), _diff_pres_offset(0.0f), - _airspeed_pub(-1), - _subsys_pub(-1), + _airspeed_pub(0), + _subsys_pub(0), _class_instance(-1), _conversion_interval(conversion_interval), _sample_perf(perf_alloc(PC_ELAPSED, "airspeed_read")), @@ -146,7 +146,7 @@ Airspeed::init() /* measurement will have generated a report, publish */ _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &arp); - if (_airspeed_pub < 0) + if (_airspeed_pub == 0) warnx("uORB started?"); } @@ -367,7 +367,7 @@ Airspeed::update_status() SUBSYSTEM_TYPE_DIFFPRESSURE }; - if (_subsys_pub > 0) { + if (_subsys_pub == 0) { orb_publish(ORB_ID(subsystem_info), _subsys_pub, &info); } else { _subsys_pub = orb_advertise(ORB_ID(subsystem_info), &info); diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp index 66f959a904..ac9912a0c2 100644 --- a/src/drivers/batt_smbus/batt_smbus.cpp +++ b/src/drivers/batt_smbus/batt_smbus.cpp @@ -203,7 +203,7 @@ BATT_SMBUS::BATT_SMBUS(int bus, uint16_t batt_smbus_addr) : _enabled(false), _work{}, _reports(nullptr), - _batt_topic(-1), + _batt_topic(0), _batt_orb_id(nullptr), _start_time(0), _batt_capacity(0) @@ -427,13 +427,13 @@ BATT_SMBUS::cycle() } // publish to orb - if (_batt_topic != -1) { + if (_batt_topic != 0) { orb_publish(_batt_orb_id, _batt_topic, &new_report); } else { _batt_topic = orb_advertise(_batt_orb_id, &new_report); - if (_batt_topic < 0) { + if (_batt_topic == 0) { errx(1, "ADVERT FAIL"); } } diff --git a/src/drivers/bma180/bma180.cpp b/src/drivers/bma180/bma180.cpp index f4e4622adc..99cadc818d 100644 --- a/src/drivers/bma180/bma180.cpp +++ b/src/drivers/bma180/bma180.cpp @@ -238,7 +238,7 @@ BMA180::BMA180(int bus, spi_dev_e device) : _reports(nullptr), _accel_range_scale(0.0f), _accel_range_m_s2(0.0f), - _accel_topic(-1), + _accel_topic(0), _class_instance(-1), _current_lowpass(0), _current_range(0), @@ -733,7 +733,7 @@ BMA180::measure() poll_notify(POLLIN); /* publish for subscribers */ - if (_accel_topic > 0 && !(_pub_blocked)) + if (_accel_topic != 0 && !(_pub_blocked)) orb_publish(ORB_ID(sensor_accel), _accel_topic, &report); /* stop the perf counter */ diff --git a/src/drivers/gimbal/gimbal.cpp b/src/drivers/gimbal/gimbal.cpp index db016b363a..eea26417bc 100644 --- a/src/drivers/gimbal/gimbal.cpp +++ b/src/drivers/gimbal/gimbal.cpp @@ -180,7 +180,7 @@ Gimbal::Gimbal() : _attitude_compensation_pitch(true), _attitude_compensation_yaw(true), _initialized(false), - _actuator_controls_2_topic(-1), + _actuator_controls_2_topic(0), _sample_perf(perf_alloc(PC_ELAPSED, "gimbal_read")), _comms_errors(perf_alloc(PC_COUNT, "gimbal_comms_errors")), _buffer_overflows(perf_alloc(PC_COUNT, "gimbal_buffer_overflows")) @@ -197,7 +197,6 @@ Gimbal::~Gimbal() /* make sure we are truly inactive */ stop(); - ::close(_actuator_controls_2_topic); ::close(_vehicle_command_sub); } @@ -281,7 +280,7 @@ Gimbal::cycle() zero_report.timestamp = hrt_absolute_time(); _actuator_controls_2_topic = orb_advertise(ORB_ID(actuator_controls_2), &zero_report); - if (_actuator_controls_2_topic < 0) { + if (_actuator_controls_2_topic == 0) { warnx("advert err"); } diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index 965c0e3e5d..3934a24808 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -175,9 +175,9 @@ GPS::GPS(const char *uart_path, bool fake_gps, bool enable_sat_info) : _mode(GPS_DRIVER_MODE_UBX), _Helper(nullptr), _Sat_Info(nullptr), - _report_gps_pos_pub(-1), + _report_gps_pos_pub(0), _p_report_sat_info(nullptr), - _report_sat_info_pub(-1), + _report_sat_info_pub(0), _rate(0.0f), _fake_gps(fake_gps) { diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp index 0e706efc21..16f861350c 100644 --- a/src/drivers/hil/hil.cpp +++ b/src/drivers/hil/hil.cpp @@ -805,7 +805,7 @@ fake(int argc, char *argv[]) orb_advert_t handle = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &ac); - if (handle < 0) { + if (handle == 0) { puts("advertise failed"); return 1; } diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index 2d3be15833..d9192bfdbb 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -360,7 +360,7 @@ HMC5883::HMC5883(device::Device *interface, const char *path, enum Rotation rota _collect_phase(false), _class_instance(-1), _orb_class_instance(-1), - _mag_topic(-1), + _mag_topic(0), _sample_perf(perf_alloc(PC_ELAPSED, "hmc5883_read")), _comms_errors(perf_alloc(PC_COUNT, "hmc5883_comms_errors")), _buffer_overflows(perf_alloc(PC_COUNT, "hmc5883_buffer_overflows")), @@ -986,14 +986,14 @@ HMC5883::collect() if (!(_pub_blocked)) { - if (_mag_topic != -1) { + if (_mag_topic != 0) { /* publish it */ orb_publish(ORB_ID(sensor_mag), _mag_topic, &new_report); } else { _mag_topic = orb_advertise_multi(ORB_ID(sensor_mag), &new_report, &_orb_class_instance, (sensor_is_onboard) ? ORB_PRIO_HIGH : ORB_PRIO_MAX); - if (_mag_topic < 0) + if (_mag_topic == 0) debug("ADVERT FAIL"); } } diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp index f1b12b0678..16256b05d2 100644 --- a/src/drivers/hott/messages.cpp +++ b/src/drivers/hott/messages.cpp @@ -63,7 +63,7 @@ static int _sensor_sub = -1; static int _airspeed_sub = -1; static int _esc_sub = -1; -static orb_advert_t _esc_pub; +static orb_advert_t _esc_pub = 0; static bool _home_position_set = false; static double _home_lat = 0.0d; diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index f276b67f00..810fa9135d 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -411,7 +411,7 @@ L3GD20::L3GD20(int bus, const char* path, spi_dev_e device, enum Rotation rotati _gyro_scale{}, _gyro_range_scale(0.0f), _gyro_range_rad_s(0.0f), - _gyro_topic(-1), + _gyro_topic(0), _orb_class_instance(-1), _class_instance(-1), _current_rate(0), @@ -490,7 +490,7 @@ L3GD20::init() _gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &grp, &_orb_class_instance, (is_external()) ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT); - if (_gyro_topic < 0) { + if (_gyro_topic == 0) { debug("failed to create sensor_gyro publication"); } diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index 8a77eeb917..df80f26d7a 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -563,7 +563,7 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rota _mag_range_ga(0.0f), _mag_range_scale(0.0f), _mag_samplerate(0), - _accel_topic(-1), + _accel_topic(0), _accel_orb_class_instance(-1), _accel_class_instance(-1), _accel_read(0), @@ -676,7 +676,7 @@ LSM303D::init() _mag->_mag_topic = orb_advertise_multi(ORB_ID(sensor_mag), &mrp, &_mag->_mag_orb_class_instance, ORB_PRIO_LOW); - if (_mag->_mag_topic < 0) { + if (_mag->_mag_topic == 0) { warnx("ADVERT ERR"); } @@ -691,7 +691,7 @@ LSM303D::init() _accel_topic = orb_advertise_multi(ORB_ID(sensor_accel), &arp, &_accel_orb_class_instance, (is_external()) ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT); - if (_accel_topic < 0) { + if (_accel_topic == 0) { warnx("ADVERT ERR"); } @@ -1770,7 +1770,7 @@ LSM303D::test_error() LSM303D_mag::LSM303D_mag(LSM303D *parent) : CDev("LSM303D_mag", LSM303D_DEVICE_PATH_MAG), _parent(parent), - _mag_topic(-1), + _mag_topic(0), _mag_orb_class_instance(-1), _mag_class_instance(-1) { diff --git a/src/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp index afeb8e5545..a191ec0be2 100644 --- a/src/drivers/mb12xx/mb12xx.cpp +++ b/src/drivers/mb12xx/mb12xx.cpp @@ -211,7 +211,7 @@ MB12XX::MB12XX(int bus, int address) : _collect_phase(false), _class_instance(-1), _orb_class_instance(-1), - _distance_sensor_topic(-1), + _distance_sensor_topic(nullptr), _sample_perf(perf_alloc(PC_ELAPSED, "mb12xx_read")), _comms_errors(perf_alloc(PC_COUNT, "mb12xx_comms_errors")), _buffer_overflows(perf_alloc(PC_COUNT, "mb12xx_buffer_overflows")), @@ -276,7 +276,7 @@ MB12XX::init() _distance_sensor_topic = orb_advertise_multi(ORB_ID(distance_sensor), &ds_report, &_orb_class_instance, ORB_PRIO_LOW); - if (_distance_sensor_topic < 0) { + if (_distance_sensor_topic == nullptr) { log("failed to create distance_sensor object. Did you start uOrb?"); } } @@ -588,7 +588,7 @@ MB12XX::collect() report.id = 0; /* publish it, if we are the primary */ - if (_distance_sensor_topic >= 0) { + if (_distance_sensor_topic != nullptr) { orb_publish(ORB_ID(distance_sensor), _distance_sensor_topic, &report); } diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index d1484a2f01..c9ca1843e5 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -641,7 +641,6 @@ MK::task_main() } - ::close(_t_esc_status); ::close(_t_actuators); ::close(_t_actuator_armed); diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 7049bd0788..b2bec363e7 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -507,7 +507,7 @@ MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev _accel_scale{}, _accel_range_scale(0.0f), _accel_range_m_s2(0.0f), - _accel_topic(-1), + _accel_topic(0), _accel_orb_class_instance(-1), _accel_class_instance(-1), _gyro_reports(nullptr), @@ -658,7 +658,7 @@ MPU6000::init() _accel_topic = orb_advertise_multi(ORB_ID(sensor_accel), &arp, &_accel_orb_class_instance, (is_external()) ? ORB_PRIO_MAX : ORB_PRIO_HIGH); - if (_accel_topic < 0) { + if (_accel_topic == 0) { warnx("ADVERT FAIL"); } @@ -670,7 +670,7 @@ MPU6000::init() _gyro->_gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &grp, &_gyro->_gyro_orb_class_instance, (is_external()) ? ORB_PRIO_MAX : ORB_PRIO_HIGH); - if (_gyro->_gyro_topic < 0) { + if (_gyro->_gyro_topic == 0) { warnx("ADVERT FAIL"); } @@ -1847,7 +1847,7 @@ MPU6000::print_registers() MPU6000_gyro::MPU6000_gyro(MPU6000 *parent, const char *path) : CDev("MPU6000_gyro", path), _parent(parent), - _gyro_topic(-1), + _gyro_topic(0), _gyro_orb_class_instance(-1), _gyro_class_instance(-1) { diff --git a/src/drivers/ms5611/ms5611_nuttx.cpp b/src/drivers/ms5611/ms5611_nuttx.cpp index cf96a7a95b..050eb5be46 100644 --- a/src/drivers/ms5611/ms5611_nuttx.cpp +++ b/src/drivers/ms5611/ms5611_nuttx.cpp @@ -224,7 +224,7 @@ MS5611::MS5611(device::Device *interface, ms5611::prom_u &prom_buf, const char* _OFF(0), _SENS(0), _msl_pressure(101325), - _baro_topic(-1), + _baro_topic(0), _orb_class_instance(-1), _class_instance(-1), _sample_perf(perf_alloc(PC_ELAPSED, "ms5611_read")), @@ -322,7 +322,7 @@ MS5611::init() &_orb_class_instance, (is_external()) ? ORB_PRIO_HIGH : ORB_PRIO_DEFAULT); - if (_baro_topic < 0) { + if (_baro_topic == 0) { warnx("failed to create sensor_baro publication"); } diff --git a/src/drivers/ms5611/ms5611_posix.cpp b/src/drivers/ms5611/ms5611_posix.cpp index 9e99d926e2..701765c84b 100644 --- a/src/drivers/ms5611/ms5611_posix.cpp +++ b/src/drivers/ms5611/ms5611_posix.cpp @@ -223,7 +223,7 @@ MS5611::MS5611(device::Device *interface, ms5611::prom_u &prom_buf, const char* _OFF(0), _SENS(0), _msl_pressure(101325), - _baro_topic(-1), + _baro_topic(0), _orb_class_instance(-1), _class_instance(-1), _sample_perf(perf_alloc(PC_ELAPSED, "ms5611_read")), @@ -325,7 +325,7 @@ MS5611::init() _baro_topic = orb_advertise_multi(ORB_ID(sensor_baro), &brp, &_orb_class_instance, (is_external()) ? ORB_PRIO_HIGH : ORB_PRIO_DEFAULT); - if (_baro_topic == (orb_advert_t)(-1)) { + if (_baro_topic == 0) { warnx("failed to create sensor_baro publication"); } //warnx("sensor_baro publication %ld", _baro_topic); diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp index db721afe32..d4cfec9a39 100644 --- a/src/drivers/px4flow/px4flow.cpp +++ b/src/drivers/px4flow/px4flow.cpp @@ -193,8 +193,8 @@ PX4FLOW::PX4FLOW(int bus, int address, enum Rotation rotation) : _collect_phase(false), _class_instance(-1), _orb_class_instance(-1), - _px4flow_topic(-1), - _distance_sensor_topic(-1), + _px4flow_topic(nullptr), + _distance_sensor_topic(nullptr), _sample_perf(perf_alloc(PC_ELAPSED, "px4flow_read")), _comms_errors(perf_alloc(PC_COUNT, "px4flow_comms_errors")), _buffer_overflows(perf_alloc(PC_COUNT, "px4flow_buffer_overflows")), @@ -517,7 +517,7 @@ PX4FLOW::collect() float zeroval = 0.0f; rotate_3f(_sensor_rotation, report.pixel_flow_x_integral, report.pixel_flow_y_integral, zeroval); - if (_px4flow_topic < 0) { + if (_px4flow_topic == 0) { _px4flow_topic = orb_advertise(ORB_ID(optical_flow), &report); } else { diff --git a/src/drivers/sf0x/sf0x.cpp b/src/drivers/sf0x/sf0x.cpp index 431184d046..e117927022 100644 --- a/src/drivers/sf0x/sf0x.cpp +++ b/src/drivers/sf0x/sf0x.cpp @@ -200,7 +200,7 @@ SF0X::SF0X(const char *port) : _last_read(0), _class_instance(-1), _orb_class_instance(-1), - _distance_sensor_topic(-1), + _distance_sensor_topic(nullptr), _consecutive_fail_count(0), _sample_perf(perf_alloc(PC_ELAPSED, "sf0x_read")), _comms_errors(perf_alloc(PC_COUNT, "sf0x_comms_errors")), @@ -293,6 +293,7 @@ SF0X::init() _class_instance = register_class_devname(RANGE_FINDER_BASE_DEVICE_PATH); +<<<<<<< HEAD if (_class_instance == CLASS_DEVICE_PRIMARY) { /* get a publish handle on the range finder topic */ struct distance_sensor_s ds_report = {}; @@ -303,6 +304,10 @@ SF0X::init() if (_distance_sensor_topic < 0) { log("failed to create distance_sensor object. Did you start uOrb?"); } +======= + if (_range_finder_topic == 0) { + warnx("advert err"); +>>>>>>> extensive orb_advert_t fixes } } while(0); diff --git a/src/drivers/trone/trone.cpp b/src/drivers/trone/trone.cpp index 23e52547a1..992669fffb 100644 --- a/src/drivers/trone/trone.cpp +++ b/src/drivers/trone/trone.cpp @@ -238,7 +238,7 @@ TRONE::TRONE(int bus, int address) : _collect_phase(false), _class_instance(-1), _orb_class_instance(-1), - _distance_sensor_topic(-1), + _distance_sensor_topic(0), _sample_perf(perf_alloc(PC_ELAPSED, "trone_read")), _comms_errors(perf_alloc(PC_COUNT, "trone_comms_errors")), _buffer_overflows(perf_alloc(PC_COUNT, "trone_buffer_overflows")) @@ -301,7 +301,7 @@ TRONE::init() _distance_sensor_topic = orb_advertise_multi(ORB_ID(distance_sensor), &ds_report, &_orb_class_instance, ORB_PRIO_LOW); - if (_distance_sensor_topic < 0) { + if (_distance_sensor_topic == 0) { log("failed to create distance_sensor object. Did you start uOrb?"); } } @@ -587,7 +587,7 @@ TRONE::collect() report.id = 0; /* publish it, if we are the primary */ - if (_distance_sensor_topic >= 0) { + if (_distance_sensor_topic != nullptr) { orb_publish(ORB_ID(distance_sensor), _distance_sensor_topic, &report); } @@ -621,9 +621,9 @@ TRONE::start() true, SUBSYSTEM_TYPE_RANGEFINDER }; - static orb_advert_t pub = -1; + static orb_advert_t pub = nullptr; - if (pub > 0) { + if (pub != nullptr) { orb_publish(ORB_ID(subsystem_info), pub, &info); } else { diff --git a/src/examples/hwtest/hwtest.c b/src/examples/hwtest/hwtest.c index 298f13e842..a403f2fa24 100644 --- a/src/examples/hwtest/hwtest.c +++ b/src/examples/hwtest/hwtest.c @@ -63,7 +63,7 @@ int ex_hwtest_main(int argc, char *argv[]) struct actuator_controls_s actuators; memset(&actuators, 0, sizeof(actuators)); - orb_advert_t actuator_pub_fd = orb_advertise(ORB_ID(actuator_controls_0), &actuators); + orb_advert_t actuator_pub_ptr = orb_advertise(ORB_ID(actuator_controls_0), &actuators); struct actuator_armed_s arm; memset(&arm, 0 , sizeof(arm)); @@ -71,8 +71,8 @@ int ex_hwtest_main(int argc, char *argv[]) arm.timestamp = hrt_absolute_time(); arm.ready_to_arm = true; arm.armed = true; - orb_advert_t arm_pub_fd = orb_advertise(ORB_ID(actuator_armed), &arm); - orb_publish(ORB_ID(actuator_armed), arm_pub_fd, &arm); + orb_advert_t arm_pub_ptr = orb_advertise(ORB_ID(actuator_armed), &arm); + orb_publish(ORB_ID(actuator_armed), arm_pub_ptr, &arm); /* read back values to validate */ int arm_sub_fd = orb_subscribe(ORB_ID(actuator_armed)); @@ -118,7 +118,7 @@ int ex_hwtest_main(int argc, char *argv[]) } actuators.timestamp = hrt_absolute_time(); - orb_publish(ORB_ID(actuator_controls_0), actuator_pub_fd, &actuators); + orb_publish(ORB_ID(actuator_controls_0), actuator_pub_ptr, &actuators); usleep(10000); } diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp index f9099cd167..9d46cf5744 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp @@ -114,7 +114,7 @@ private: int _sensors_sub = -1; int _params_sub = -1; int _global_pos_sub = -1; - orb_advert_t _att_pub = -1; + orb_advert_t _att_pub = 0; struct { param_t w_acc; @@ -327,7 +327,7 @@ void AttitudeEstimatorQ::task_main() { memcpy(&att.R[0], R.data, sizeof(att.R)); att.R_valid = true; - if (_att_pub < 0) { + if (_att_pub == 0) { _att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att); } else { orb_publish(ORB_ID(vehicle_attitude), _att_pub, &att); diff --git a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp index 68a61488f9..c8c740e273 100755 --- a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp +++ b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp @@ -432,8 +432,6 @@ int attitude_estimator_so3_thread_main(int argc, char *argv[]) int sub_control_mode = orb_subscribe(ORB_ID(vehicle_control_mode)); /* advertise attitude */ - //orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att); - //orb_advert_t att_pub = -1; orb_advert_t att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att); int loopcounter = 0; diff --git a/src/modules/bottle_drop/bottle_drop.cpp b/src/modules/bottle_drop/bottle_drop.cpp index 987b930d28..3a94de899d 100644 --- a/src/modules/bottle_drop/bottle_drop.cpp +++ b/src/modules/bottle_drop/bottle_drop.cpp @@ -180,7 +180,7 @@ BottleDrop::BottleDrop() : _command {}, _global_pos {}, ref {}, - _actuator_pub(-1), + _actuator_pub(0), _actuators {}, _drop_approval(false), _doors_opened(0), @@ -190,7 +190,7 @@ BottleDrop::BottleDrop() : _drop_position {}, _drop_state(DROP_STATE_INIT), _onboard_mission {}, - _onboard_mission_pub(-1) + _onboard_mission_pub(0) { } diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index f81cbfb2b6..d924256401 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -934,7 +934,7 @@ int commander_thread_main(int argc, char *argv[]) /* publish initial state */ status_pub = orb_advertise(ORB_ID(vehicle_status), &status); - if (status_pub < 0) { + if (status_pub == 0) { warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n"); warnx("exiting."); px4_task_exit(ERROR); @@ -952,12 +952,12 @@ int commander_thread_main(int argc, char *argv[]) armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed); /* home position */ - orb_advert_t home_pub = -1; + orb_advert_t home_pub = 0; struct home_position_s home; memset(&home, 0, sizeof(home)); /* init mission state, do it here to allow navigator to use stored mission even if mavlink failed to start */ - orb_advert_t mission_pub = -1; + orb_advert_t mission_pub = 0; mission_s mission; if (dm_read(DM_KEY_MISSION_STATE, 0, &mission, sizeof(mission_s)) == sizeof(mission_s)) { @@ -2124,7 +2124,6 @@ int commander_thread_main(int argc, char *argv[]) close(diff_pres_sub); close(param_changed_sub); close(battery_sub); - close(mission_pub); thread_running = false; diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index c04d79f4e7..a12f78b32c 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -129,11 +129,11 @@ AttitudePositionEstimatorEKF::AttitudePositionEstimatorEKF() : _armedSub(-1), /* publications */ - _att_pub(-1), - _global_pos_pub(-1), - _local_pos_pub(-1), - _estimator_status_pub(-1), - _wind_pub(-1), + _att_pub(0), + _global_pos_pub(0), + _local_pos_pub(0), + _estimator_status_pub(0), + _wind_pub(0), _att({}), _gyro({}), diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp index cb17728948..387956f693 100644 --- a/src/modules/fw_att_control/fw_att_control_main.cpp +++ b/src/modules/fw_att_control/fw_att_control_main.cpp @@ -337,10 +337,10 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() : _vehicle_status_sub(-1), /* publications */ - _rate_sp_pub(-1), - _attitude_sp_pub(-1), - _actuators_0_pub(-1), - _actuators_2_pub(-1), + _rate_sp_pub(0), + _attitude_sp_pub(0), + _actuators_0_pub(0), + _actuators_2_pub(0), _rates_sp_id(0), _actuators_id(0), diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 3525c5674b..fc21fc9b5d 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -434,9 +434,9 @@ FixedwingPositionControl::FixedwingPositionControl() : _sensor_combined_sub(-1), /* publications */ - _attitude_sp_pub(-1), - _tecs_status_pub(-1), - _nav_capabilities_pub(-1), + _attitude_sp_pub(0), + _tecs_status_pub(0), + _nav_capabilities_pub(0), /* states */ _att(), diff --git a/src/modules/land_detector/LandDetector.cpp b/src/modules/land_detector/LandDetector.cpp index 7c830fc072..d7e2f8101f 100644 --- a/src/modules/land_detector/LandDetector.cpp +++ b/src/modules/land_detector/LandDetector.cpp @@ -44,7 +44,7 @@ #include LandDetector::LandDetector() : - _landDetectedPub(-1), + _landDetectedPub(0), _landDetected({0, false}), _taskShouldExit(false), _taskIsRunning(false) @@ -55,7 +55,6 @@ LandDetector::LandDetector() : LandDetector::~LandDetector() { _taskShouldExit = true; - close(_landDetectedPub); } void LandDetector::shutdown() diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index 442d36dfba..5546996edb 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -81,7 +81,7 @@ MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : MavlinkStream(m _transfer_partner_compid(0), _offboard_mission_sub(-1), _mission_result_sub(-1), - _offboard_mission_pub(-1), + _offboard_mission_pub(0), _slow_rate_limiter(_interval / 10.0f), _verbose(false) { @@ -93,7 +93,6 @@ MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : MavlinkStream(m MavlinkMissionManager::~MavlinkMissionManager() { - close(_offboard_mission_pub); close(_mission_result_sub); } @@ -150,7 +149,7 @@ MavlinkMissionManager::update_active_mission(int dataman_id, unsigned count, int _current_seq = seq; /* mission state saved successfully, publish offboard_mission topic */ - if (_offboard_mission_pub < 0) { + if (_offboard_mission_pub == 0) { _offboard_mission_pub = orb_advertise(ORB_ID(offboard_mission), &mission); } else { diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index 524effb205..5c13629513 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -45,7 +45,7 @@ MavlinkParametersManager::MavlinkParametersManager(Mavlink *mavlink) : MavlinkStream(mavlink), _send_all_index(-1), - _rc_param_map_pub(-1), + _rc_param_map_pub(0), _rc_param_map() { } @@ -162,7 +162,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) } _rc_param_map.timestamp = hrt_absolute_time(); - if (_rc_param_map_pub < 0) { + if (_rc_param_map_pub == 0) { _rc_param_map_pub = orb_advertise(ORB_ID(rc_parameter_map), &_rc_param_map); } else { diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 8a9b426484..d9b666a003 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -95,34 +95,34 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) : hil_local_pos{}, hil_land_detector{}, _control_mode{}, - _global_pos_pub(-1), - _local_pos_pub(-1), - _attitude_pub(-1), - _gps_pub(-1), - _sensors_pub(-1), - _gyro_pub(-1), - _accel_pub(-1), - _mag_pub(-1), - _baro_pub(-1), - _airspeed_pub(-1), - _battery_pub(-1), - _cmd_pub(-1), - _flow_pub(-1), - _distance_sensor_pub(-1), - _offboard_control_mode_pub(-1), - _actuator_controls_pub(-1), - _global_vel_sp_pub(-1), - _att_sp_pub(-1), - _rates_sp_pub(-1), - _force_sp_pub(-1), - _pos_sp_triplet_pub(-1), - _vicon_position_pub(-1), - _vision_position_pub(-1), - _telemetry_status_pub(-1), - _rc_pub(-1), - _manual_pub(-1), - _land_detector_pub(-1), - _time_offset_pub(-1), + _global_pos_pub(0), + _local_pos_pub(0), + _attitude_pub(0), + _gps_pub(0), + _sensors_pub(0), + _gyro_pub(0), + _accel_pub(0), + _mag_pub(0), + _baro_pub(0), + _airspeed_pub(0), + _battery_pub(0), + _cmd_pub(0), + _flow_pub(0), + _distance_sensor_pub(0), + _offboard_control_mode_pub(0), + _actuator_controls_pub(0), + _global_vel_sp_pub(0), + _att_sp_pub(0), + _rates_sp_pub(0), + _force_sp_pub(0), + _pos_sp_triplet_pub(0), + _vicon_position_pub(0), + _vision_position_pub(0), + _telemetry_status_pub(0), + _rc_pub(0), + _manual_pub(0), + _land_detector_pub(0), + _time_offset_pub(0), _control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))), _hil_frames(0), _old_timestamp(0), @@ -314,7 +314,7 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg) vcmd.source_component = msg->compid; vcmd.confirmation = cmd_mavlink.confirmation; - if (_cmd_pub < 0) { + if (_cmd_pub == 0) { _cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd); } else { @@ -370,7 +370,7 @@ MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg) vcmd.source_system = msg->sysid; vcmd.source_component = msg->compid; - if (_cmd_pub < 0) { + if (_cmd_pub == 0) { _cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd); } else { @@ -410,7 +410,7 @@ MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg) float zeroval = 0.0f; rotate_3f(flow_rot, f.pixel_flow_x_integral, f.pixel_flow_y_integral, zeroval); - if (_flow_pub < 0) { + if (_flow_pub == 0) { _flow_pub = orb_advertise(ORB_ID(optical_flow), &f); } else { @@ -461,7 +461,7 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg) f.sensor_id = flow.sensor_id; f.gyro_temperature = flow.temperature; - if (_flow_pub < 0) { + if (_flow_pub == 0) { _flow_pub = orb_advertise(ORB_ID(optical_flow), &f); } else { @@ -515,7 +515,7 @@ MavlinkReceiver::handle_message_set_mode(mavlink_message_t *msg) vcmd.source_component = msg->compid; vcmd.confirmation = 1; - if (_cmd_pub < 0) { + if (_cmd_pub == 0) { _cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd); } else { @@ -570,7 +570,7 @@ MavlinkReceiver::handle_message_vicon_position_estimate(mavlink_message_t *msg) vicon_position.pitch = pos.pitch; vicon_position.yaw = pos.yaw; - if (_vicon_position_pub < 0) { + if (_vicon_position_pub == 0) { _vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position); } else { @@ -605,7 +605,7 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t offboard_control_mode.timestamp = hrt_absolute_time(); - if (_offboard_control_mode_pub < 0) { + if (_offboard_control_mode_pub == 0) { _offboard_control_mode_pub = orb_advertise(ORB_ID(offboard_control_mode), &offboard_control_mode); } else { @@ -630,7 +630,7 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t force_sp.y = set_position_target_local_ned.afy; force_sp.z = set_position_target_local_ned.afz; //XXX: yaw - if (_force_sp_pub < 0) { + if (_force_sp_pub == 0) { _force_sp_pub = orb_advertise(ORB_ID(vehicle_force_setpoint), &force_sp); } else { orb_publish(ORB_ID(vehicle_force_setpoint), _force_sp_pub, &force_sp); @@ -697,7 +697,7 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t //XXX handle global pos setpoints (different MAV frames) - if (_pos_sp_triplet_pub < 0) { + if (_pos_sp_triplet_pub == 0) { _pos_sp_triplet_pub = orb_advertise(ORB_ID(position_setpoint_triplet), &pos_sp_triplet); } else { @@ -740,7 +740,7 @@ MavlinkReceiver::handle_message_set_actuator_control_target(mavlink_message_t *m offboard_control_mode.timestamp = hrt_absolute_time(); - if (_offboard_control_mode_pub < 0) { + if (_offboard_control_mode_pub == 0) { _offboard_control_mode_pub = orb_advertise(ORB_ID(offboard_control_mode), &offboard_control_mode); } else { orb_publish(ORB_ID(offboard_control_mode), _offboard_control_mode_pub, &offboard_control_mode); @@ -763,7 +763,7 @@ MavlinkReceiver::handle_message_set_actuator_control_target(mavlink_message_t *m actuator_controls.control[i] = set_actuator_control_target.controls[i]; } - if (_actuator_controls_pub < 0) { + if (_actuator_controls_pub == 0) { _actuator_controls_pub = orb_advertise(ORB_ID(actuator_controls_0), &actuator_controls); } else { orb_publish(ORB_ID(actuator_controls_0), _actuator_controls_pub, &actuator_controls); @@ -804,7 +804,7 @@ MavlinkReceiver::handle_message_vision_position_estimate(mavlink_message_t *msg) vision_position.q[2] = q(2); vision_position.q[3] = q(3); - if (_vision_position_pub < 0) { + if (_vision_position_pub == 0) { _vision_position_pub = orb_advertise(ORB_ID(vision_position_estimate), &vision_position); } else { @@ -857,7 +857,7 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg) _offboard_control_mode.timestamp = hrt_absolute_time(); - if (_offboard_control_mode_pub < 0) { + if (_offboard_control_mode_pub == 0) { _offboard_control_mode_pub = orb_advertise(ORB_ID(offboard_control_mode), &_offboard_control_mode); } else { @@ -892,7 +892,7 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg) _att_sp.thrust = set_attitude_target.thrust; } - if (_att_sp_pub < 0) { + if (_att_sp_pub == 0) { _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &_att_sp); } else { orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &_att_sp); @@ -912,7 +912,7 @@ MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg) _rates_sp.thrust = set_attitude_target.thrust; } - if (_att_sp_pub < 0) { + if (_att_sp_pub == 0) { _rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &_rates_sp); } else { orb_publish(ORB_ID(vehicle_rates_setpoint), _rates_sp_pub, &_rates_sp); @@ -948,7 +948,7 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) tstatus.system_id = msg->sysid; tstatus.component_id = msg->compid; - if (_telemetry_status_pub < 0) { + if (_telemetry_status_pub == 0) { _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus); } else { @@ -974,7 +974,7 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg) // warnx("pitch: %.2f, roll: %.2f, yaw: %.2f, throttle: %.2f", (double)manual.x, (double)manual.y, (double)manual.r, (double)manual.z); - if (_manual_pub < 0) { + if (_manual_pub == 0) { _manual_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual); } else { @@ -1001,7 +1001,7 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg) tstatus.timestamp = hrt_absolute_time(); tstatus.heartbeat_time = tstatus.timestamp; - if (_telemetry_status_pub < 0) { + if (_telemetry_status_pub == 0) { _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus); } else { @@ -1105,7 +1105,7 @@ MavlinkReceiver::handle_message_timesync(mavlink_message_t *msg) tsync_offset.offset_ns = _time_offset ; - if (_time_offset_pub < 0) { + if (_time_offset_pub == 0) { _time_offset_pub = orb_advertise(ORB_ID(time_offset), &tsync_offset); } else { @@ -1135,7 +1135,7 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) airspeed.indicated_airspeed_m_s = ias; airspeed.true_airspeed_m_s = tas; - if (_airspeed_pub < 0) { + if (_airspeed_pub == 0) { _airspeed_pub = orb_advertise(ORB_ID(airspeed), &airspeed); } else { @@ -1157,7 +1157,7 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) gyro.z = imu.zgyro; gyro.temperature = imu.temperature; - if (_gyro_pub < 0) { + if (_gyro_pub == 0) { _gyro_pub = orb_advertise(ORB_ID(sensor_gyro), &gyro); } else { @@ -1179,7 +1179,7 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) accel.z = imu.zacc; accel.temperature = imu.temperature; - if (_accel_pub < 0) { + if (_accel_pub == 0) { _accel_pub = orb_advertise(ORB_ID(sensor_accel), &accel); } else { @@ -1200,7 +1200,7 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) mag.y = imu.ymag; mag.z = imu.zmag; - if (_mag_pub < 0) { + if (_mag_pub == 0) { /* publish to the first mag topic */ _mag_pub = orb_advertise(ORB_ID(sensor_mag), &mag); @@ -1219,7 +1219,7 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) baro.altitude = imu.pressure_alt; baro.temperature = imu.temperature; - if (_baro_pub < 0) { + if (_baro_pub == 0) { _baro_pub = orb_advertise(ORB_ID(sensor_baro), &baro); } else { @@ -1275,7 +1275,7 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) hil_sensors.differential_pressure_timestamp = timestamp; /* publish combined sensor topic */ - if (_sensors_pub < 0) { + if (_sensors_pub == 0) { _sensors_pub = orb_advertise(ORB_ID(sensor_combined), &hil_sensors); } else { @@ -1294,7 +1294,7 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) hil_battery_status.current_a = 10.0f; hil_battery_status.discharged_mah = -1.0f; - if (_battery_pub < 0) { + if (_battery_pub == 0) { _battery_pub = orb_advertise(ORB_ID(battery_status), &hil_battery_status); } else { @@ -1348,7 +1348,7 @@ MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg) hil_gps.fix_type = gps.fix_type; hil_gps.satellites_used = gps.satellites_visible; //TODO: rename mavlink_hil_gps_t sats visible to used? - if (_gps_pub < 0) { + if (_gps_pub == 0) { _gps_pub = orb_advertise(ORB_ID(vehicle_gps_position), &hil_gps); } else { @@ -1373,7 +1373,7 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg) airspeed.indicated_airspeed_m_s = hil_state.ind_airspeed * 1e-2f; airspeed.true_airspeed_m_s = hil_state.true_airspeed * 1e-2f; - if (_airspeed_pub < 0) { + if (_airspeed_pub == 0) { _airspeed_pub = orb_advertise(ORB_ID(airspeed), &airspeed); } else { @@ -1406,7 +1406,7 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg) hil_attitude.pitchspeed = hil_state.pitchspeed; hil_attitude.yawspeed = hil_state.yawspeed; - if (_attitude_pub < 0) { + if (_attitude_pub == 0) { _attitude_pub = orb_advertise(ORB_ID(vehicle_attitude), &hil_attitude); } else { @@ -1430,7 +1430,7 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg) hil_global_pos.eph = 2.0f; hil_global_pos.epv = 4.0f; - if (_global_pos_pub < 0) { + if (_global_pos_pub == 0) { _global_pos_pub = orb_advertise(ORB_ID(vehicle_global_position), &hil_global_pos); } else { @@ -1471,7 +1471,7 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg) hil_local_pos.xy_global = true; hil_local_pos.z_global = true; - if (_local_pos_pub < 0) { + if (_local_pos_pub == 0) { _local_pos_pub = orb_advertise(ORB_ID(vehicle_local_position), &hil_local_pos); } else { @@ -1486,7 +1486,7 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg) hil_land_detector.landed = landed; hil_land_detector.timestamp = hrt_absolute_time(); - if (_land_detector_pub < 0) { + if (_land_detector_pub == 0) { _land_detector_pub = orb_advertise(ORB_ID(vehicle_land_detected), &hil_land_detector); } else { @@ -1509,7 +1509,7 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg) accel.z = hil_state.zacc; accel.temperature = 25.0f; - if (_accel_pub < 0) { + if (_accel_pub == 0) { _accel_pub = orb_advertise(ORB_ID(sensor_accel), &accel); } else { @@ -1528,7 +1528,7 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg) hil_battery_status.current_a = 10.0f; hil_battery_status.discharged_mah = -1.0f; - if (_battery_pub < 0) { + if (_battery_pub == 0) { _battery_pub = orb_advertise(ORB_ID(battery_status), &hil_battery_status); } else { diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index d65694224b..965c746960 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -314,10 +314,10 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() : _vehicle_status_sub(-1), /* publications */ - _att_sp_pub(-1), - _v_rates_sp_pub(-1), - _actuators_0_pub(-1), - _controller_status_pub(-1), + _att_sp_pub(0), + _v_rates_sp_pub(0), + _actuators_0_pub(0), + _controller_status_pub(0), _rates_sp_id(0), _actuators_id(0), diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index b6ad4fd547..c77c33a849 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -307,9 +307,9 @@ MulticopterPositionControl::MulticopterPositionControl() : _global_vel_sp_sub(-1), /* publications */ - _att_sp_pub(-1), - _local_pos_sp_pub(-1), - _global_vel_sp_pub(-1), + _att_sp_pub(0), + _local_pos_sp_pub(0), + _global_vel_sp_pub(0), _ref_alt(0.0f), _ref_timestamp(0), diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp index 70d93b953d..993b059a94 100644 --- a/src/modules/navigator/geofence.cpp +++ b/src/modules/navigator/geofence.cpp @@ -69,7 +69,7 @@ static const int ERROR = -1; Geofence::Geofence() : SuperBlock(NULL, "GF"), - _fence_pub(-1), + _fence_pub(0), _home_pos{}, _home_pos_set(false), _last_horizontal_range_warning(0), @@ -317,7 +317,7 @@ Geofence::addPoint(int argc, char *argv[]) void Geofence::publishFence(unsigned vertices) { - if (_fence_pub == -1) { + if (_fence_pub == 0) { _fence_pub = orb_advertise(ORB_ID(fence), &vertices); } else { diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 4971d6bc29..e0083d50d5 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -108,10 +108,10 @@ Navigator::Navigator() : _onboard_mission_sub(-1), _offboard_mission_sub(-1), _param_update_sub(-1), - _pos_sp_triplet_pub(-1), - _mission_result_pub(-1), - _geofence_result_pub(-1), - _att_sp_pub(-1), + _pos_sp_triplet_pub(0), + _mission_result_pub(0), + _geofence_result_pub(0), + _att_sp_pub(0), _vstatus{}, _control_mode{}, _global_pos{}, diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c index 9dc7999099..4cadd638bc 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -343,7 +343,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) /* advertise */ orb_advert_t vehicle_local_position_pub = orb_advertise(ORB_ID(vehicle_local_position), &local_pos); - orb_advert_t vehicle_global_position_pub = -1; + orb_advert_t vehicle_global_position_pub = 0; struct position_estimator_inav_params params; struct position_estimator_inav_param_handles pos_inav_param_handles; @@ -1158,7 +1158,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) global_pos.eph = eph; global_pos.epv = epv; - if (vehicle_global_position_pub < 0) { + if (vehicle_global_position_pub == 0) { vehicle_global_position_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos); } else { diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 5ccadde57f..8bc885eb8c 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -373,8 +373,7 @@ int sdlog2_main(int argc, char *argv[]) cmd.param1 = -1; cmd.param2 = -1; cmd.param3 = 1; - int fd = orb_advertise(ORB_ID(vehicle_command), &cmd); - close(fd); + orb_advertise(ORB_ID(vehicle_command), &cmd); return 0; } @@ -384,8 +383,7 @@ int sdlog2_main(int argc, char *argv[]) cmd.param1 = -1; cmd.param2 = -1; cmd.param3 = 2; - int fd = orb_advertise(ORB_ID(vehicle_command), &cmd); - close(fd); + orb_advertise(ORB_ID(vehicle_command), &cmd); return 0; } diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index cf1f51c9dd..83ef0ff4ee 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -517,13 +517,13 @@ Sensors::Sensors() : _manual_control_sub(-1), /* publications */ - _sensor_pub(-1), - _manual_control_pub(-1), - _actuator_group_3_pub(-1), - _rc_pub(-1), - _battery_pub(-1), - _airspeed_pub(-1), - _diff_pres_pub(-1), + _sensor_pub(0), + _manual_control_pub(0), + _actuator_group_3_pub(0), + _rc_pub(0), + _battery_pub(0), + _airspeed_pub(0), + _diff_pres_pub(0), /* performance counters */ _loop_perf(perf_alloc(PC_ELAPSED, "sensor task update")), diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index ed4a6343fe..837208eaff 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -157,7 +157,7 @@ void Simulator::handle_message(mavlink_message_t *msg) { fill_sensors_from_imu_msg(&_sensor, &imu); // publish message - if(_sensor_combined_pub < 0) { + if(_sensor_combined_pub == 0) { _sensor_combined_pub = orb_advertise(ORB_ID(sensor_combined), &_sensor); } else { orb_publish(ORB_ID(sensor_combined), _sensor_combined_pub, &_sensor); @@ -171,7 +171,7 @@ void Simulator::handle_message(mavlink_message_t *msg) { fill_manual_control_sp_msg(&_manual_control_sp, &man_ctrl_sp); // publish message - if(_manual_control_sp_pub < 0) { + if(_manual_control_sp_pub == 0) { _manual_control_sp_pub = orb_advertise(ORB_ID(manual_control_setpoint), &_manual_control_sp); } else { orb_publish(ORB_ID(manual_control_setpoint), _manual_control_sp_pub, &_manual_control_sp); diff --git a/src/modules/systemlib/param/param.c b/src/modules/systemlib/param/param.c index 09e9e88870..f5af2e27df 100644 --- a/src/modules/systemlib/param/param.c +++ b/src/modules/systemlib/param/param.c @@ -130,7 +130,7 @@ const UT_icd param_icd = {sizeof(struct param_wbuf_s), NULL, NULL, NULL}; ORB_DEFINE(parameter_update, struct parameter_update_s); /** parameter update topic handle */ -static orb_advert_t param_topic = -1; +static orb_advert_t param_topic = 0; static void param_set_used_internal(param_t param); @@ -233,7 +233,7 @@ param_notify_changes(void) * If we don't have a handle to our topic, create one now; otherwise * just publish. */ - if (param_topic == -1) { + if (param_topic == 0) { param_topic = orb_advertise(ORB_ID(parameter_update), &pup); } else { diff --git a/src/modules/uORB/uORB.h b/src/modules/uORB/uORB.h index a8b19d91f9..63571488b8 100644 --- a/src/modules/uORB/uORB.h +++ b/src/modules/uORB/uORB.h @@ -135,7 +135,7 @@ __BEGIN_DECLS * a file-descriptor-based handle would not otherwise be in scope for the * publisher. */ -typedef intptr_t orb_advert_t; +typedef uintptr_t orb_advert_t; /** * Advertise as the publisher of a topic. diff --git a/src/modules/uORB/uORBManager_nuttx.cpp b/src/modules/uORB/uORBManager_nuttx.cpp index 85746c0c27..479103fe7d 100644 --- a/src/modules/uORB/uORBManager_nuttx.cpp +++ b/src/modules/uORB/uORBManager_nuttx.cpp @@ -89,18 +89,18 @@ orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, /* open the node as an advertiser */ fd = node_open(PUBSUB, meta, data, true, instance, priority); if (fd == ERROR) - return ERROR; + return 0; /* get the advertiser handle and close the node */ result = ioctl(fd, ORBIOCGADVERTISER, (unsigned long)&advertiser); close(fd); if (result == ERROR) - return ERROR; + return 0; /* the advertiser must perform an initial publish to initialise the object */ result = orb_publish(meta, advertiser, data); if (result == ERROR) - return ERROR; + return 0; return advertiser; } diff --git a/src/modules/uORB/uORBManager_posix.cpp b/src/modules/uORB/uORBManager_posix.cpp index a9dad24dcd..bcb36470fe 100644 --- a/src/modules/uORB/uORBManager_posix.cpp +++ b/src/modules/uORB/uORBManager_posix.cpp @@ -94,7 +94,7 @@ orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, fd = node_open(PUBSUB, meta, data, true, instance, priority); if (fd == ERROR) { warnx("node_open as advertiser failed."); - return ERROR; + return 0; } /* get the advertiser handle and close the node */ @@ -102,14 +102,14 @@ orb_advert_t uORB::Manager::orb_advertise_multi(const struct orb_metadata *meta, px4_close(fd); if (result == ERROR) { warnx("px4_ioctl ORBIOCGADVERTISER failed. fd = %d", fd); - return ERROR; + return 0; } /* the advertiser must perform an initial publish to initialise the object */ result = orb_publish(meta, advertiser, data); if (result == ERROR) { warnx("orb_publish failed"); - return ERROR; + return 0; } return advertiser; diff --git a/src/modules/uORB/uORBTest_UnitTest.cpp b/src/modules/uORB/uORBTest_UnitTest.cpp index 722f538976..edb7994e8f 100644 --- a/src/modules/uORB/uORBTest_UnitTest.cpp +++ b/src/modules/uORB/uORBTest_UnitTest.cpp @@ -137,16 +137,17 @@ int uORBTest::UnitTest::pubsublatency_main(void) int uORBTest::UnitTest::test() { struct orb_test t, u; - int pfd, sfd; + int sfd; + orb_advert_t ptopic; bool updated; t.val = 0; - pfd = orb_advertise(ORB_ID(orb_test), &t); + ptopic = orb_advertise(ORB_ID(orb_test), &t); - if (pfd < 0) + if (ptopic == 0) return test_fail("advertise failed: %d", errno); - test_note("publish handle 0x%08x", pfd); + test_note("publish handle 0x%08x", ptopic); sfd = orb_subscribe(ORB_ID(orb_test)); if (sfd < 0) @@ -170,7 +171,7 @@ int uORBTest::UnitTest::test() t.val = 2; test_note("try publish"); - if (PX4_OK != orb_publish(ORB_ID(orb_test), pfd, &t)) + if (PX4_OK != orb_publish(ORB_ID(orb_test), ptopic, &t)) return test_fail("publish failed"); if (PX4_OK != orb_check(sfd, &updated)) @@ -186,7 +187,6 @@ int uORBTest::UnitTest::test() return test_fail("copy(2) mismatch: %d expected %d", u.val, t.val); orb_unsubscribe(sfd); - close(pfd); /* this routine tests the multi-topic support */ test_note("try multi-topic support"); @@ -197,7 +197,7 @@ int uORBTest::UnitTest::test() test_note("advertised"); int instance1; - int pfd1 = orb_advertise_multi(ORB_ID(orb_multitest), &t, &instance1, ORB_PRIO_MIN); + orb_advert_t pfd1 = orb_advertise_multi(ORB_ID(orb_multitest), &t, &instance1, ORB_PRIO_MIN); if (instance0 != 0) return test_fail("mult. id0: %d", instance0); diff --git a/src/modules/uORB/uORBTest_UnitTest.hpp b/src/modules/uORB/uORBTest_UnitTest.hpp index f19c95451d..93399f734f 100644 --- a/src/modules/uORB/uORBTest_UnitTest.hpp +++ b/src/modules/uORB/uORBTest_UnitTest.hpp @@ -98,7 +98,7 @@ int uORBTest::UnitTest::latency_test(orb_id_t T, bool print) t.val = 308; t.time = hrt_absolute_time(); - int pfd0 = orb_advertise(T, &t); + orb_advert_t pfd0 = orb_advertise(T, &t); char * const args[1] = { NULL }; @@ -128,8 +128,6 @@ int uORBTest::UnitTest::latency_test(orb_id_t T, bool print) usleep(1000); } - px4_close(pfd0); - if (pubsub_task < 0) { return test_fail("failed launching task"); } diff --git a/src/modules/uavcan/sensors/gnss.cpp b/src/modules/uavcan/sensors/gnss.cpp index 3ae07367fa..cd8b52862e 100644 --- a/src/modules/uavcan/sensors/gnss.cpp +++ b/src/modules/uavcan/sensors/gnss.cpp @@ -48,7 +48,7 @@ const char *const UavcanGnssBridge::NAME = "gnss"; UavcanGnssBridge::UavcanGnssBridge(uavcan::INode &node) : _node(node), _sub_fix(node), -_report_pub(-1) +_report_pub(0) { } diff --git a/src/modules/uavcan/sensors/sensor_bridge.cpp b/src/modules/uavcan/sensors/sensor_bridge.cpp index b370764440..419f671eb3 100644 --- a/src/modules/uavcan/sensors/sensor_bridge.cpp +++ b/src/modules/uavcan/sensors/sensor_bridge.cpp @@ -119,7 +119,7 @@ void UavcanCDevSensorBridgeBase::publish(const int node_id, const void *report) channel->class_instance = class_instance; channel->orb_advert = orb_advertise_multi(_orb_topic, report, &channel->orb_instance, ORB_PRIO_HIGH); - if (channel->orb_advert < 0) { + if (channel->orb_advert == 0) { log("ADVERTISE FAILED"); (void)unregister_class_devname(_class_devname, class_instance); *channel = Channel(); diff --git a/src/modules/vtol_att_control/vtol_att_control_main.cpp b/src/modules/vtol_att_control/vtol_att_control_main.cpp index 11aa88a5f3..bbb1037fbd 100644 --- a/src/modules/vtol_att_control/vtol_att_control_main.cpp +++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp @@ -230,10 +230,10 @@ VtolAttitudeControl::VtolAttitudeControl() : _battery_status_sub(-1), //init publication handlers - _actuators_0_pub(-1), - _actuators_1_pub(-1), - _vtol_vehicle_status_pub(-1), - _v_rates_sp_pub(-1), + _actuators_0_pub(0), + _actuators_1_pub(0), + _vtol_vehicle_status_pub(0), + _v_rates_sp_pub(0), _loop_perf(perf_alloc(PC_ELAPSED, "vtol_att_control")), _nonfinite_input_perf(perf_alloc(PC_COUNT, "vtol att control nonfinite input")) diff --git a/src/platforms/posix/drivers/accelsim/accelsim.cpp b/src/platforms/posix/drivers/accelsim/accelsim.cpp index c68371c315..9722b79a56 100644 --- a/src/platforms/posix/drivers/accelsim/accelsim.cpp +++ b/src/platforms/posix/drivers/accelsim/accelsim.cpp @@ -369,7 +369,7 @@ ACCELSIM::ACCELSIM(const char* path, enum Rotation rotation) : _mag_range_ga(0.0f), _mag_range_scale(0.0f), _mag_samplerate(0), - _accel_topic(-1), + _accel_topic(0), _accel_orb_class_instance(-1), _accel_class_instance(-1), _accel_read(0), @@ -496,7 +496,7 @@ ACCELSIM::init() _accel_topic = orb_advertise_multi(ORB_ID(sensor_accel), &arp, &_accel_orb_class_instance, ORB_PRIO_DEFAULT); - if (_accel_topic == (orb_advert_t)(-1)) { + if (_accel_topic == 0) { PX4_WARN("ADVERT ERR"); } @@ -1077,7 +1077,7 @@ ACCELSIM::measure() // The first call to measure() is from init() and _accel_topic is not // yet initialized - if (_accel_topic != (orb_advert_t)(-1)) { + if (_accel_topic != 0) { orb_publish(ORB_ID(sensor_accel), _accel_topic, &accel_report); } } diff --git a/src/platforms/posix/drivers/airspeedsim/airspeedsim.cpp b/src/platforms/posix/drivers/airspeedsim/airspeedsim.cpp index d0cf702a77..8cea970885 100644 --- a/src/platforms/posix/drivers/airspeedsim/airspeedsim.cpp +++ b/src/platforms/posix/drivers/airspeedsim/airspeedsim.cpp @@ -83,8 +83,8 @@ Airspeed::Airspeed(int bus, int address, unsigned conversion_interval, const cha _measure_ticks(0), _collect_phase(false), _diff_pres_offset(0.0f), - _airspeed_pub(-1), - _subsys_pub(-1), + _airspeed_pub(0), + _subsys_pub(0), _class_instance(-1), _conversion_interval(conversion_interval), _sample_perf(perf_alloc(PC_ELAPSED, "airspeed_read")), @@ -143,7 +143,7 @@ Airspeed::init() /* measurement will have generated a report, publish */ _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &arp); - if (_airspeed_pub < 0) + if (_airspeed_pub == 0) PX4_WARN("uORB started?"); } diff --git a/src/platforms/posix/drivers/barosim/baro.cpp b/src/platforms/posix/drivers/barosim/baro.cpp index dbabec9c4b..6492c9606b 100644 --- a/src/platforms/posix/drivers/barosim/baro.cpp +++ b/src/platforms/posix/drivers/barosim/baro.cpp @@ -213,7 +213,7 @@ BAROSIM::BAROSIM(device::Device *interface, barosim::prom_u &prom_buf, const cha _OFF(0), _SENS(0), _msl_pressure(101325), - _baro_topic(-1), + _baro_topic(0), _orb_class_instance(-1), _class_instance(-1), _sample_perf(perf_alloc(PC_ELAPSED, "barosim_read")), @@ -315,7 +315,7 @@ BAROSIM::init() _baro_topic = orb_advertise_multi(ORB_ID(sensor_baro), &brp, &_orb_class_instance, (is_external()) ? ORB_PRIO_HIGH : ORB_PRIO_DEFAULT); - if (_baro_topic == (orb_advert_t)(-1)) { + if (_baro_topic == 0) { PX4_ERR("failed to create sensor_baro publication"); } //PX4_WARN("sensor_baro publication %ld", _baro_topic); @@ -722,7 +722,7 @@ BAROSIM::collect() /* publish it */ if (!(_pub_blocked)) { - if (_baro_topic != (orb_advert_t)(-1)) { + if (_baro_topic != 0) { /* publish it */ orb_publish(ORB_ID(sensor_baro), _baro_topic, &report); } diff --git a/src/platforms/posix/drivers/gyrosim/gyrosim.cpp b/src/platforms/posix/drivers/gyrosim/gyrosim.cpp index 80cef4c867..619c74c6b3 100644 --- a/src/platforms/posix/drivers/gyrosim/gyrosim.cpp +++ b/src/platforms/posix/drivers/gyrosim/gyrosim.cpp @@ -472,7 +472,7 @@ GYROSIM::GYROSIM(const char *path_accel, const char *path_gyro, enum Rotation ro _accel_scale{}, _accel_range_scale(0.0f), _accel_range_m_s2(0.0f), - _accel_topic(-1), + _accel_topic(0), _accel_orb_class_instance(-1), _accel_class_instance(-1), _gyro_reports(nullptr), @@ -624,7 +624,7 @@ GYROSIM::init() _accel_topic = orb_advertise_multi(ORB_ID(sensor_accel), &arp, &_accel_orb_class_instance, ORB_PRIO_HIGH); - if (_accel_topic < 0) { + if (_accel_topic == 0) { PX4_WARN("ADVERT FAIL"); } @@ -636,7 +636,7 @@ GYROSIM::init() _gyro->_gyro_topic = orb_advertise_multi(ORB_ID(sensor_gyro), &grp, &_gyro->_gyro_orb_class_instance, ORB_PRIO_HIGH); - if (_gyro->_gyro_topic < 0) { + if (_gyro->_gyro_topic == 0) { PX4_WARN("ADVERT FAIL"); } @@ -1547,7 +1547,7 @@ GYROSIM::print_registers() GYROSIM_gyro::GYROSIM_gyro(GYROSIM *parent, const char *path) : VDev("GYROSIM_gyro", path), _parent(parent), - _gyro_topic(-1), + _gyro_topic(0), _gyro_orb_class_instance(-1), _gyro_class_instance(-1) { diff --git a/src/systemcmds/motor_test/motor_test.c b/src/systemcmds/motor_test/motor_test.c index b77730ef16..d5def7056b 100644 --- a/src/systemcmds/motor_test/motor_test.c +++ b/src/systemcmds/motor_test/motor_test.c @@ -59,7 +59,7 @@ __EXPORT int motor_test_main(int argc, char *argv[]); static void motor_test(unsigned channel, float value); static void usage(const char *reason); -static orb_advert_t _test_motor_pub; +static orb_advert_t _test_motor_pub = 0; void motor_test(unsigned channel, float value) {