12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576 |
- #pragma once
- #include "SIM_Aircraft.h"
- #include <SITL/SITL.h>
- #include <AP_HAL/utility/RingBuffer.h>
- namespace SITL {
- class Vicon {
- public:
- Vicon();
-
- void update(const Location &loc, const Vector3f &position, const Quaternion &attitude);
-
-
- int fd() { return fd_their_end; }
- private:
- SITL *_sitl;
-
- const uint8_t system_id = 17;
- const uint8_t component_id = 18;
-
- const mavlink_channel_t mavlink_ch = (mavlink_channel_t)(MAVLINK_COMM_0+5);
- int fd_their_end;
- int fd_my_end;
- uint64_t last_observation_usec;
- uint64_t time_send_us;
- uint64_t time_offset_us;
- mavlink_message_t obs_msg;
- struct obs_elements {
- uint32_t time_ms;
- Vector3f position;
- Quaternion attitude;
- };
- void update_vicon_position_estimate(const Location &loc,
- const Vector3f &position,
- const Quaternion &attitude);
- void maybe_send_heartbeat();
- uint32_t last_heartbeat_ms;
- bool init_sitl_pointer();
- };
- }
|