APM:Libraries
SIM_Vicon.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  simple particle sensor simulation
17 */
18 
19 #pragma once
20 
21 #include "SIM_Aircraft.h"
22 
23 #include <SITL/SITL.h>
24 
26 
27 namespace SITL {
28 
29 class Vicon {
30 public:
31 
32  Vicon();
33 
34  // update state
35  void update(const Location &loc, const Vector3f &position, const Quaternion &attitude);
36 
37  // return fd on which data from the device can be read, and data
38  // to the device can be written
39  int fd() { return fd_their_end; }
40 
41 private:
42 
44 
45  // TODO: make these parameters:
46  const uint8_t system_id = 17;
47  const uint8_t component_id = 18;
48 
49  // we share channels with the ArduPilot binary!
50  const mavlink_channel_t mavlink_ch = (mavlink_channel_t)(MAVLINK_COMM_0+5);
51 
53  int fd_my_end;
54 
56  uint64_t time_send_us;
57  uint64_t time_offset_us;
58  mavlink_message_t obs_msg;
59 
60  struct obs_elements {
61  uint32_t time_ms; // measurement timestamp (msec)
64  };
65 
67  const Vector3f &position,
68  const Quaternion &attitude);
69 
70  void maybe_send_heartbeat();
72 
73  bool init_sitl_pointer();
74 };
75 
76 }
int fd()
Definition: SIM_Vicon.h:39
int fd_my_end
Definition: SIM_Vicon.h:53
void update_vicon_position_estimate(const Location &loc, const Vector3f &position, const Quaternion &attitude)
Definition: SIM_Vicon.cpp:68
void update(const Location &loc, const Vector3f &position, const Quaternion &attitude)
Definition: SIM_Vicon.cpp:134
uint64_t time_send_us
Definition: SIM_Vicon.h:56
void maybe_send_heartbeat()
Definition: SIM_Vicon.cpp:47
SITL * _sitl
Definition: SIM_Vicon.h:43
const uint8_t system_id
Definition: SIM_Vicon.h:46
int fd_their_end
Definition: SIM_Vicon.h:52
const uint8_t component_id
Definition: SIM_Vicon.h:47
uint64_t time_offset_us
Definition: SIM_Vicon.h:57
bool init_sitl_pointer()
Definition: SIM_Vicon.cpp:120
uint64_t last_observation_usec
Definition: SIM_Vicon.h:55
mavlink_message_t obs_msg
Definition: SIM_Vicon.h:58
uint32_t last_heartbeat_ms
Definition: SIM_Vicon.h:71
const mavlink_channel_t mavlink_ch
Definition: SIM_Vicon.h:50