SITL: switch vicon simulation to use VISION_POSITION_ESTIMATE
this is a more commonly used message
This commit is contained in:
parent
e474b7dcfe
commit
9672dce335
@ -26,6 +26,9 @@
|
||||
|
||||
using namespace SITL;
|
||||
|
||||
#define USE_VISION_POSITION_ESTIMATE 1
|
||||
|
||||
|
||||
Vicon::Vicon()
|
||||
{
|
||||
int tmp[2];
|
||||
@ -104,6 +107,22 @@ void Vicon::update_vicon_position_estimate(const Location &loc,
|
||||
float yaw;
|
||||
attitude.to_euler(roll, pitch, yaw);
|
||||
|
||||
#if USE_VISION_POSITION_ESTIMATE
|
||||
// use the more recent VISION_POSITION_ESTIMATE message
|
||||
mavlink_msg_vision_position_estimate_pack_chan(
|
||||
system_id,
|
||||
component_id,
|
||||
mavlink_ch,
|
||||
&obs_msg,
|
||||
now_us + time_offset_us,
|
||||
position.x,
|
||||
position.y,
|
||||
position.z,
|
||||
roll,
|
||||
pitch,
|
||||
yaw,
|
||||
NULL, 0);
|
||||
#else
|
||||
mavlink_msg_vicon_position_estimate_pack_chan(
|
||||
system_id,
|
||||
component_id,
|
||||
@ -117,6 +136,7 @@ void Vicon::update_vicon_position_estimate(const Location &loc,
|
||||
pitch,
|
||||
yaw,
|
||||
NULL);
|
||||
#endif // USE_VISION_POSITION_ESTIMATE
|
||||
|
||||
uint32_t delay_ms = 25 + unsigned(random()) % 300;
|
||||
time_send_us = now_us + delay_ms * 1000UL;
|
||||
|
Loading…
Reference in New Issue
Block a user