APM:Libraries
SIM_Gimbal.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  gimbal simulator class for MAVLink gimbal
17 */
18 
19 #include "SIM_Gimbal.h"
20 
21 #include <stdio.h>
22 
23 #include "SIM_Aircraft.h"
24 
25 extern const AP_HAL::HAL& hal;
26 
27 namespace SITL {
28 
29 Gimbal::Gimbal(const struct sitl_fdm &_fdm) :
30  fdm(_fdm),
31  target_address("127.0.0.1"),
32  target_port(5762),
33  lower_joint_limits(radians(-40), radians(-135), radians(-7.5)),
34  upper_joint_limits(radians(40), radians(45), radians(7.5)),
35  travelLimitGain(20),
36  reporting_period_ms(10),
37  seen_heartbeat(false),
38  seen_gimbal_control(false),
39  mav_socket(false)
40 {
41  memset(&mavlink, 0, sizeof(mavlink));
43 }
44 
45 
46 /*
47  update the gimbal state
48 */
49 void Gimbal::update(void)
50 {
51  // calculate delta time in seconds
52  uint32_t now_us = AP_HAL::micros();
53 
54  float delta_t = (now_us - last_update_us) * 1.0e-6f;
55  last_update_us = now_us;
56 
57  Matrix3f vehicle_dcm;
58  fdm.quaternion.rotation_matrix(vehicle_dcm);
59 
60  Vector3f vehicle_gyro = Vector3f(radians(fdm.rollRate),
63  Vector3f vehicle_accel_body = Vector3f(fdm.xAccel, fdm.yAccel, fdm.zAccel);
64 
65  // take a copy of the demanded rates to bypass the limiter function for testing
66  Vector3f demRateRaw = demanded_angular_rate;
67 
68  // 1) Rotate the copters rotation rates into the gimbals frame of reference
69  // copterAngRate_G = transpose(DCMgimbal)*DCMcopter*copterAngRate
70  Vector3f copterAngRate_G = dcm.transposed()*vehicle_dcm*vehicle_gyro;
71 
72  // 2) Subtract the copters body rates to obtain a copter relative rotational
73  // rate vector (X,Y,Z) in gimbal sensor frame
74  // relativeGimbalRate(X,Y,Z) = gimbalRateDemand - copterAngRate_G
75  Vector3f relativeGimbalRate = demanded_angular_rate - copterAngRate_G;
76 
77  // calculate joint angles (euler312 order)
78  // calculate copter -> gimbal rotation matrix
79  Matrix3f rotmat_copter_gimbal = dcm.transposed() * vehicle_dcm;
80 
81  joint_angles = rotmat_copter_gimbal.transposed().to_euler312();
82 
83  /* 4) For each of the three joints, calculate upper and lower rate limits
84  from the corresponding angle limits and current joint angles
85 
86  upperRatelimit = (jointAngle - lowerAngleLimit) * travelLimitGain
87  lowerRatelimit = (jointAngle - upperAngleLimit) * travelLimitGain
88 
89  travelLimitGain is equal to the inverse of the bump stop time constant and
90  should be set to something like 20 initially. If set too high it can cause
91  the rates to 'ring' when they the limiter is in force, particularly given
92  we are using a first order numerical integration.
93  */
96 
97  /*
98  5) Calculate the gimbal joint rates (roll, elevation, azimuth)
99 
100  gimbalJointRates(roll, elev, azimuth) = Matrix*relativeGimbalRate(X,Y,Z)
101 
102  where matrix =
103  +- -+
104  | cos(elevAngle), 0, sin(elevAngle) |
105  | |
106  | sin(elevAngle) tan(rollAngle), 1, -cos(elevAngle) tan(rollAngle) |
107  | |
108  | sin(elevAngle) cos(elevAngle) |
109  | - --------------, 0, -------------- |
110  | cos(rollAngle) cos(rollAngle) |
111  +- -+
112  */
113  float rollAngle = joint_angles.x;
114  float elevAngle = joint_angles.y;
115  Matrix3f matrix = Matrix3f(Vector3f(cosf(elevAngle), 0, sinf(elevAngle)),
116  Vector3f(sinf(elevAngle)*tanf(rollAngle), 1, -cosf(elevAngle)*tanf(rollAngle)),
117  Vector3f(-sinf(elevAngle)/cosf(rollAngle), 0, cosf(elevAngle)/cosf(rollAngle)));
118  Vector3f gimbalJointRates = matrix * relativeGimbalRate;
119 
120  // 6) Apply the rate limits from 4)
121  gimbalJointRates.x = constrain_float(gimbalJointRates.x, lowerRatelimit.x, upperRatelimit.x);
122  gimbalJointRates.y = constrain_float(gimbalJointRates.y, lowerRatelimit.y, upperRatelimit.y);
123  gimbalJointRates.z = constrain_float(gimbalJointRates.z, lowerRatelimit.z, upperRatelimit.z);
124  /*
125  7) Convert the modified gimbal joint rates to body rates (still copter
126  relative)
127  relativeGimbalRate(X,Y,Z) = Matrix * gimbalJointRates(roll, elev, azimuth)
128 
129  where Matrix =
130 
131  +- -+
132  | cos(elevAngle), 0, -cos(rollAngle) sin(elevAngle) |
133  | |
134  | 0, 1, sin(rollAngle) |
135  | |
136  | sin(elevAngle), 0, cos(elevAngle) cos(rollAngle) |
137  +- -+
138  */
139  matrix = Matrix3f(Vector3f(cosf(elevAngle), 0, -cosf(rollAngle)*sinf(elevAngle)),
140  Vector3f(0, 1, sinf(rollAngle)),
141  Vector3f(sinf(elevAngle), 0, cosf(elevAngle)*cosf(rollAngle)));
142  relativeGimbalRate = matrix * gimbalJointRates;
143 
144  // 8) Add to the result from step 1) to obtain the demanded gimbal body rates
145  // in an inertial frame of reference
146  // demandedGimbalRatesInertial(X,Y,Z) = relativeGimbalRate(X,Y,Z) + copterAngRate_G
147  // Vector3f demandedGimbalRatesInertial = relativeGimbalRate + copterAngRate_G;
148 
149  // for the moment we will set gyros equal to demanded_angular_rate
150  gimbal_angular_rate = demRateRaw; // demandedGimbalRatesInertial + true_gyro_bias - supplied_gyro_bias
151 
152  // update rotation of the gimbal
153  dcm.rotate(gimbal_angular_rate*delta_t);
154  dcm.normalize();
155 
156  // calculate copter -> gimbal rotation matrix
157  rotmat_copter_gimbal = dcm.transposed() * vehicle_dcm;
158 
159  // calculate joint angles (euler312 order)
160  joint_angles = rotmat_copter_gimbal.transposed().to_euler312();
161 
162  // update observed gyro
164 
165  // update delta_angle (integrate)
166  delta_angle += gyro * delta_t;
167 
168  // calculate accel in gimbal body frame
169  Vector3f copter_accel_earth = vehicle_dcm * vehicle_accel_body;
170  Vector3f accel = dcm.transposed() * copter_accel_earth;
171 
172  // integrate velocity
173  delta_velocity += accel * delta_t;
174 
175  // see if we should do a report
176  send_report();
177 }
178 
179 /*
180  send a report to the vehicle control code over MAVLink
181 */
183 {
184  if (AP_HAL::millis() < 10000) {
185  // simulated aircraft don't appear until 10s after startup. This avoids a windows
186  // threading issue with non-blocking sockets and the initial wait on uartA
187  return;
188  }
189  if (!mavlink.connected && mav_socket.connect(target_address, target_port)) {
190  ::printf("Gimbal connected to %s:%u\n", target_address, (unsigned)target_port);
191  mavlink.connected = true;
192  }
193  if (!mavlink.connected) {
194  return;
195  }
196 
197  // check for incoming MAVLink messages
198  uint8_t buf[100];
199  ssize_t ret;
200 
201  while ((ret=mav_socket.recv(buf, sizeof(buf), 0)) > 0) {
202  for (uint8_t i=0; i<ret; i++) {
203  mavlink_message_t msg;
204  mavlink_status_t status;
205  if (mavlink_frame_char_buffer(&mavlink.rxmsg, &mavlink.status,
206  buf[i],
207  &msg, &status) == MAVLINK_FRAMING_OK) {
208  switch (msg.msgid) {
209  case MAVLINK_MSG_ID_HEARTBEAT: {
210  if (!seen_heartbeat) {
211  seen_heartbeat = true;
212  vehicle_component_id = msg.compid;
213  vehicle_system_id = msg.sysid;
214  ::printf("Gimbal using srcSystem %u\n", (unsigned)vehicle_system_id);
215  }
216  break;
217  }
218  case MAVLINK_MSG_ID_GIMBAL_CONTROL: {
219  mavlink_gimbal_control_t pkt;
220  mavlink_msg_gimbal_control_decode(&msg, &pkt);
221  demanded_angular_rate = Vector3f(pkt.demanded_rate_x,
222  pkt.demanded_rate_y,
223  pkt.demanded_rate_z);
224  // no longer supply a bias
226  seen_gimbal_control = true;
227  break;
228  }
229  }
230  }
231  }
232  }
233 
234  if (!seen_heartbeat) {
235  return;
236  }
237  uint32_t now = AP_HAL::millis();
238  mavlink_message_t msg;
239  uint16_t len;
240 
241  if (now - last_heartbeat_ms >= 1000) {
242  mavlink_heartbeat_t heartbeat;
243  heartbeat.type = MAV_TYPE_GIMBAL;
244  heartbeat.autopilot = MAV_AUTOPILOT_ARDUPILOTMEGA;
245  heartbeat.base_mode = 0;
246  heartbeat.system_status = 0;
247  heartbeat.mavlink_version = 0;
248  heartbeat.custom_mode = 0;
249 
250  /*
251  save and restore sequence number for chan0, as it is used by
252  generated encode functions
253  */
254  mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
255  uint8_t saved_seq = chan0_status->current_tx_seq;
256  chan0_status->current_tx_seq = mavlink.seq;
257  len = mavlink_msg_heartbeat_encode(vehicle_system_id,
259  &msg, &heartbeat);
260  chan0_status->current_tx_seq = saved_seq;
261 
262  mav_socket.send(&msg.magic, len);
263  last_heartbeat_ms = now;
264  }
265 
266  /*
267  send a GIMBAL_REPORT message
268  */
269  uint32_t now_us = AP_HAL::micros();
270  if (now_us - last_report_us > reporting_period_ms*1000UL) {
271  mavlink_gimbal_report_t gimbal_report;
272  float delta_time = (now_us - last_report_us) * 1.0e-6f;
273  last_report_us = now_us;
274  gimbal_report.target_system = vehicle_system_id;
275  gimbal_report.target_component = vehicle_component_id;
276  gimbal_report.delta_time = delta_time;
277  gimbal_report.delta_angle_x = delta_angle.x;
278  gimbal_report.delta_angle_y = delta_angle.y;
279  gimbal_report.delta_angle_z = delta_angle.z;
280  gimbal_report.delta_velocity_x = delta_velocity.x;
281  gimbal_report.delta_velocity_y = delta_velocity.y;
282  gimbal_report.delta_velocity_z = delta_velocity.z;
283  gimbal_report.joint_roll = joint_angles.x;
284  gimbal_report.joint_el = joint_angles.y;
285  gimbal_report.joint_az = joint_angles.z;
286 
287  mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
288  uint8_t saved_seq = chan0_status->current_tx_seq;
289  chan0_status->current_tx_seq = mavlink.seq;
290  len = mavlink_msg_gimbal_report_encode(vehicle_system_id,
292  &msg, &gimbal_report);
293  chan0_status->current_tx_seq = saved_seq;
294 
295  uint8_t msgbuf[len];
296  len = mavlink_msg_to_send_buffer(msgbuf, &msg);
297  if (len > 0) {
298  mav_socket.send(msgbuf, len);
299  }
300 
302  delta_angle.zero();
303  }
304 }
305 
306 } // namespace SITL
int printf(const char *fmt,...)
Definition: stdio.c:113
Vector3f upper_joint_limits
Definition: SIM_Gimbal.h:59
void update(void)
Definition: SIM_Gimbal.cpp:49
Vector3< float > Vector3f
Definition: vector3.h:246
Vector3f true_gyro_bias
Definition: SIM_Gimbal.h:64
double xAccel
Definition: SITL.h:18
uint32_t last_update_us
Definition: SIM_Gimbal.h:41
const struct sitl_fdm & fdm
Definition: SIM_Gimbal.h:33
SocketAPM mav_socket
Definition: SIM_Gimbal.h:96
uint8_t vehicle_system_id
Definition: SIM_Gimbal.h:93
Vector3f lower_joint_limits
Definition: SIM_Gimbal.h:58
bool seen_heartbeat
Definition: SIM_Gimbal.h:91
Quaternion quaternion
Definition: SITL.h:21
Vector3f joint_angles
Definition: SIM_Gimbal.h:55
Matrix3< float > Matrix3f
Definition: matrix3.h:270
Vector3f gimbal_angular_rate
Definition: SIM_Gimbal.h:44
Matrix3f dcm
Definition: SIM_Gimbal.h:38
double rollRate
Definition: SITL.h:19
const uint16_t target_port
Definition: SIM_Gimbal.h:35
union UU msgbuf
Matrix3< T > transposed(void) const
Definition: matrix3.cpp:189
bool seen_gimbal_control
Definition: SIM_Gimbal.h:92
double yawRate
Definition: SITL.h:19
#define f(i)
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
Vector3< T > to_euler312() const
Definition: matrix3.cpp:81
double yAccel
Definition: SITL.h:18
T z
Definition: vector3.h:67
void send_report(void)
Definition: SIM_Gimbal.cpp:182
Gimbal(const struct sitl_fdm &_fdm)
Definition: SIM_Gimbal.cpp:29
Vector3f delta_velocity
Definition: SIM_Gimbal.h:76
double zAccel
Definition: SITL.h:18
void rotation_matrix(Matrix3f &m) const
Definition: quaternion.cpp:24
Vector3f supplied_gyro_bias
Definition: SIM_Gimbal.h:87
const float travelLimitGain
Definition: SIM_Gimbal.h:61
double pitchRate
Definition: SITL.h:19
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
static constexpr float radians(float deg)
Definition: AP_Math.h:158
uint32_t last_heartbeat_ms
Definition: SIM_Gimbal.h:90
const char * target_address
Definition: SIM_Gimbal.h:34
void rotate(const Vector3< T > &g)
Definition: matrix3.cpp:115
uint32_t last_report_us
Definition: SIM_Gimbal.h:89
mavlink_status_t status
Definition: SIM_Gimbal.h:101
void normalize(void)
Definition: matrix3.cpp:135
Vector3f delta_angle
Definition: SIM_Gimbal.h:73
struct SITL::Gimbal::@203 mavlink
const float reporting_period_ms
Definition: SIM_Gimbal.h:70
uint32_t micros()
Definition: system.cpp:152
Vector3f demanded_angular_rate
Definition: SIM_Gimbal.h:82
Vector3f gyro
Definition: SIM_Gimbal.h:47
void zero()
Definition: vector3.h:182
T x
Definition: vector3.h:67
uint8_t vehicle_component_id
Definition: SIM_Gimbal.h:94