Skip to content
Snippets Groups Projects
Commit 1b33445c authored by Daniel Agar's avatar Daniel Agar
Browse files

simulator mavlink set lpos ground truth limits to infinity

parent fc29e789
No related branches found
No related tags found
No related merge requests found
......@@ -47,6 +47,8 @@
#include <mathlib/mathlib.h>
#include <uORB/topics/vehicle_local_position.h>
#include <limits>
extern "C" __EXPORT hrt_abstime hrt_reset(void);
#define SEND_INTERVAL 20
......@@ -524,10 +526,10 @@ void Simulator::handle_message(mavlink_message_t *msg, bool publish)
hil_lpos.ref_lon = _hil_ref_lon;
hil_lpos.ref_alt = _hil_ref_alt;
hil_lpos.ref_timestamp = _hil_ref_timestamp;
hil_lpos.vxy_max = 0.0f;
hil_lpos.vz_max = 0.0f;
hil_lpos.hagl_min = 0.0f;
hil_lpos.hagl_max = 0.0f;
hil_lpos.vxy_max = std::numeric_limits<float>::infinity();
hil_lpos.vz_max = std::numeric_limits<float>::infinity();
hil_lpos.hagl_min = std::numeric_limits<float>::infinity();
hil_lpos.hagl_max = std::numeric_limits<float>::infinity();
// always publish ground truth attitude message
int hil_lpos_multi;
......@@ -535,8 +537,6 @@ void Simulator::handle_message(mavlink_message_t *msg, bool publish)
ORB_PRIO_HIGH);
}
break;
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment