forked from Archive/PX4-Autopilot
simulator mavlink: add horizontal and vertical fov + quaterion orientation
to distance sensor
This commit is contained in:
parent
02c3765c1b
commit
aff131774e
|
@ -1090,6 +1090,13 @@ int Simulator::publish_distance_topic(const mavlink_distance_sensor_t *dist_mavl
|
|||
dist.variance = dist_mavlink->covariance * 1e-4f; // cm^2 to m^2
|
||||
dist.signal_quality = -1;
|
||||
|
||||
dist.h_fov = dist_mavlink->horizontal_fov;
|
||||
dist.v_fov = dist_mavlink->vertical_fov;
|
||||
dist.q[0] = dist_mavlink->quaternion[0];
|
||||
dist.q[1] = dist_mavlink->quaternion[1];
|
||||
dist.q[2] = dist_mavlink->quaternion[2];
|
||||
dist.q[3] = dist_mavlink->quaternion[3];
|
||||
|
||||
int dist_multi;
|
||||
orb_publish_auto(ORB_ID(distance_sensor), &_dist_pub, &dist, &dist_multi, ORB_PRIO_HIGH);
|
||||
|
||||
|
|
Loading…
Reference in New Issue