|
|
|
@ -66,6 +66,8 @@
@@ -66,6 +66,8 @@
|
|
|
|
|
#include <uORB/uORB.h> |
|
|
|
|
#include <uORB/topics/distance_sensor.h> |
|
|
|
|
|
|
|
|
|
#include <systemlib/mavlink_log.h> |
|
|
|
|
|
|
|
|
|
using namespace time_literals; |
|
|
|
|
|
|
|
|
|
/* Configuration Constants */ |
|
|
|
@ -177,6 +179,8 @@ private:
@@ -177,6 +179,8 @@ private:
|
|
|
|
|
(ParamInt<px4::params::SENS_TF_10_ROT>) _p_sensor10_rot, |
|
|
|
|
(ParamInt<px4::params::SENS_TF_11_ROT>) _p_sensor11_rot |
|
|
|
|
); |
|
|
|
|
orb_advert_t _mavlink_log_pub{nullptr}; ///< mavlink log pub
|
|
|
|
|
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
TFMINI_I2C::TFMINI_I2C(I2CSPIBusOption bus_option, const int bus, int bus_frequency, int address) : |
|
|
|
@ -280,6 +284,9 @@ TFMINI_I2C::collect()
@@ -280,6 +284,9 @@ TFMINI_I2C::collect()
|
|
|
|
|
report.timestamp = hrt_absolute_time(); |
|
|
|
|
report.type = distance_sensor_s::MAV_DISTANCE_SENSOR_LASER; |
|
|
|
|
report.variance = 0.0f; |
|
|
|
|
report.h_fov = math::radians(1.15f); // 50.0f, 0.0488692f
|
|
|
|
|
report.v_fov = math::radians(1.15f); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
int instance_id; |
|
|
|
|
orb_publish_auto(ORB_ID(distance_sensor), &_distance_sensor_topic, &report, &instance_id); |
|
|
|
@ -293,6 +300,16 @@ TFMINI_I2C::collect()
@@ -293,6 +300,16 @@ TFMINI_I2C::collect()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
perf_end(_sample_perf); |
|
|
|
|
|
|
|
|
|
// static uint32_t last_2s,delt_time;
|
|
|
|
|
// uint32_t nowtime = hrt_absolute_time();
|
|
|
|
|
// if( (nowtime - last_2s) > 2_s)
|
|
|
|
|
// {
|
|
|
|
|
// mavlink_log_info(&_mavlink_log_pub, "dist(%d) : %.2f,%.2f\n",(nowtime-delt_time),(double)distance_m,(double)report.h_fov);
|
|
|
|
|
// last_2s = nowtime;
|
|
|
|
|
// }
|
|
|
|
|
// delt_time = hrt_absolute_time();
|
|
|
|
|
|
|
|
|
|
return PX4_OK; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|