APM:Libraries
SIM_Vicon.cpp
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 vicon simulator class
17 
18  XKFR
19 
20 */
21 
22 #include "SIM_Vicon.h"
23 #include <stdio.h>
24 #include <unistd.h>
25 #include <fcntl.h>
26 
27 using namespace SITL;
28 
30 {
31  int tmp[2];
32  if (pipe(tmp) == -1) {
33  AP_HAL::panic("pipe() failed");
34  }
35  fd_my_end = tmp[1];
36  fd_their_end = tmp[0];
37 
38  // make sure we don't screw the simulation up by blocking:
39  fcntl(fd_my_end, F_SETFL, fcntl(fd_my_end, F_GETFL, 0) | O_NONBLOCK);
40  fcntl(fd_their_end, F_SETFL, fcntl(fd_their_end, F_GETFL, 0) | O_NONBLOCK);
41 
42  if (!valid_channel(mavlink_ch)) {
43  AP_HAL::panic("Invalid mavlink channel");
44  }
45 }
46 
48 {
49  const uint32_t now = AP_HAL::millis();
50 
51  if (now - last_heartbeat_ms < 100) {
52  // we only provide a heartbeat every so often
53  return;
54  }
55  last_heartbeat_ms = now;
56 
57  mavlink_message_t msg;
58  mavlink_msg_heartbeat_pack(system_id,
60  &msg,
61  MAV_TYPE_GCS,
62  MAV_AUTOPILOT_INVALID,
63  0,
64  0,
65  0);
66 }
67 
69  const Vector3f &position,
70  const Quaternion &attitude)
71 {
72  const uint64_t now_us = AP_HAL::micros64();
73 
74  if (time_offset_us == 0) {
75  time_offset_us = (unsigned(random()) % 7000) * 1000000ULL;
76  printf("time_offset_us %llu\n", (long long unsigned)time_offset_us);
77  }
78 
79  if (time_send_us && now_us >= time_send_us) {
80  uint8_t msgbuf[300];
81  uint16_t msgbuf_len = mavlink_msg_to_send_buffer(msgbuf, &obs_msg);
82 
83  if (::write(fd_my_end, (void*)&msgbuf, msgbuf_len) != msgbuf_len) {
84  ::fprintf(stderr, "Vicon: write failure\n");
85  }
86  time_send_us = 0;
87  }
88  if (time_send_us != 0) {
89  // waiting for the last msg to go out
90  return;
91  }
92 
93  if (now_us - last_observation_usec < 10000) {
94  // create observations at 10ms
95  return;
96  }
97 
98  float roll;
99  float pitch;
100  float yaw;
101  attitude.to_euler(roll, pitch, yaw);
102 
103  mavlink_msg_vicon_position_estimate_pack_chan(
104  system_id,
105  component_id,
106  mavlink_ch,
107  &obs_msg,
108  now_us + time_offset_us,
109  position.x,
110  position.y,
111  position.z,
112  roll,
113  pitch,
114  yaw);
115 
116  uint32_t delay_ms = 25 + unsigned(random()) % 300;
117  time_send_us = now_us + delay_ms * 1000UL;
118 }
119 
121 {
122  if (_sitl == nullptr) {
123  _sitl = (SITL *)AP_Param::find_object("SIM_");
124  if (_sitl == nullptr) {
125  return false;
126  }
127  }
128  return true;
129 }
130 
131 /*
132  update vicon sensor state
133  */
134 void Vicon::update(const Location &loc, const Vector3f &position, const Quaternion &attitude)
135 {
136  if (!init_sitl_pointer()) {
137  return;
138  }
139 
141  update_vicon_position_estimate(loc, position, attitude);
142 }
143 
void to_euler(float &roll, float &pitch, float &yaw) const
Definition: quaternion.cpp:272
int printf(const char *fmt,...)
Definition: stdio.c:113
static AP_Param * find_object(const char *name)
Definition: AP_Param.cpp:939
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
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
void maybe_send_heartbeat()
Definition: SIM_Vicon.cpp:47
union UU msgbuf
SITL * _sitl
Definition: SIM_Vicon.h:43
const uint8_t system_id
Definition: SIM_Vicon.h:46
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
T z
Definition: vector3.h:67
int fd_their_end
Definition: SIM_Vicon.h:52
uint64_t micros64()
Definition: system.cpp:162
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
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
mavlink_message_t obs_msg
Definition: SIM_Vicon.h:58
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
uint32_t last_heartbeat_ms
Definition: SIM_Vicon.h:71
const mavlink_channel_t mavlink_ch
Definition: SIM_Vicon.h:50
T x
Definition: vector3.h:67