Browse Source

Merge pull request #4052 from PX4/revert_sonar_pub

Revert "px4flow: disable distance data transmission from px4flow sensor"
sbg
James Goppert 9 years ago
parent
commit
2cf5fb8fb0
  1. 24
      src/drivers/px4flow/px4flow.cpp

24
src/drivers/px4flow/px4flow.cpp

@ -240,17 +240,17 @@ PX4FLOW::init()
return ret; return ret;
} }
//_class_instance = register_class_devname(RANGE_FINDER_BASE_DEVICE_PATH); _class_instance = register_class_devname(RANGE_FINDER_BASE_DEVICE_PATH);
/* get a publish handle on the range finder topic */ /* get a publish handle on the range finder topic */
//struct distance_sensor_s ds_report = {}; struct distance_sensor_s ds_report = {};
//_distance_sensor_topic = orb_advertise_multi(ORB_ID(distance_sensor), &ds_report, _distance_sensor_topic = orb_advertise_multi(ORB_ID(distance_sensor), &ds_report,
// &_orb_class_instance, ORB_PRIO_HIGH); &_orb_class_instance, ORB_PRIO_HIGH);
//if (_distance_sensor_topic == nullptr) { if (_distance_sensor_topic == nullptr) {
// DEVICE_LOG("failed to create distance_sensor object. Did you start uOrb?"); DEVICE_LOG("failed to create distance_sensor object. Did you start uOrb?");
//} }
ret = OK; ret = OK;
/* sensor is ok, but we don't really know if it is within range */ /* sensor is ok, but we don't really know if it is within range */
@ -554,18 +554,18 @@ PX4FLOW::collect()
} }
/* publish to the distance_sensor topic as well */ /* publish to the distance_sensor topic as well */
/*struct distance_sensor_s distance_report; struct distance_sensor_s distance_report;
distance_report.timestamp = report.timestamp; distance_report.timestamp = report.timestamp;
distance_report.min_distance = PX4FLOW_MIN_DISTANCE; distance_report.min_distance = PX4FLOW_MIN_DISTANCE;
distance_report.max_distance = PX4FLOW_MAX_DISTANCE; distance_report.max_distance = PX4FLOW_MAX_DISTANCE;
distance_report.current_distance = report.ground_distance_m; distance_report.current_distance = report.ground_distance_m;
distance_report.covariance = 0.0f; distance_report.covariance = 0.0f;
distance_report.type = distance_sensor_s::MAV_DISTANCE_SENSOR_ULTRASOUND; distance_report.type = distance_sensor_s::MAV_DISTANCE_SENSOR_ULTRASOUND;
*//* TODO: the ID needs to be properly set */ /* TODO: the ID needs to be properly set */
//distance_report.id = 0; distance_report.id = 0;
//distance_report.orientation = 8; distance_report.orientation = 8;
//orb_publish(ORB_ID(distance_sensor), _distance_sensor_topic, &distance_report); orb_publish(ORB_ID(distance_sensor), _distance_sensor_topic, &distance_report);
/* post a report to the ring */ /* post a report to the ring */
if (_reports->force(&report)) { if (_reports->force(&report)) {

Loading…
Cancel
Save