APM:Libraries
SIM_Gimbal.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  gimbal simulator class
17 */
18 
19 #pragma once
20 
21 #include <AP_HAL/utility/Socket.h>
22 
23 #include "SIM_Aircraft.h"
24 
25 namespace SITL {
26 
27 class Gimbal {
28 public:
29  Gimbal(const struct sitl_fdm &_fdm);
30  void update(void);
31 
32 private:
33  const struct sitl_fdm &fdm;
34  const char *target_address;
35  const uint16_t target_port;
36 
37  // rotation matrix (gimbal body -> earth)
39 
40  // time of last update
41  uint32_t last_update_us;
42 
43  // true angular rate of gimbal in body frame (rad/s)
45 
46  // observed angular rate (including biases)
48 
49  /* joint angles, in radians. in yaw/roll/pitch order. Relative to fwd.
50  So 0,0,0 points forward.
51  Pi/2,0,0 means pointing right
52  0, Pi/2, 0 means pointing fwd, but rolled 90 degrees to right
53  0, 0, -Pi/2, means pointing down
54  */
56 
57  // physical constraints on joint angles in (roll, pitch, azimuth) order
60 
61  const float travelLimitGain;
62 
63  // true gyro bias
65 
66  // reporting variables. gimbal pushes these to vehicle code over
67  // MAVLink at approx 100Hz
68 
69  // reporting period in ms
70  const float reporting_period_ms;
71 
72  // integral of gyro vector over last time interval. In radians
74 
75  // integral of accel vector over last time interval. In m/s
77 
78  /*
79  control variables from the vehicle
80  */
81  // angular rate in rad/s. In body frame of gimbal
83 
84  // gyro bias provided by EKF on vehicle. In rad/s.
85  // Should be subtracted from the gyro readings to get true body
86  // rotatation rates
88 
89  uint32_t last_report_us;
95 
96  SocketAPM mav_socket;
97  struct {
98  // socket to telem2 on aircraft
99  bool connected;
100  mavlink_message_t rxmsg;
101  mavlink_status_t status;
102  uint8_t seq;
103  } mavlink;
104 
105  void send_report(void);
106 };
107 
108 } // namespace SITL
Vector3f upper_joint_limits
Definition: SIM_Gimbal.h:59
void update(void)
Definition: SIM_Gimbal.cpp:49
Vector3f true_gyro_bias
Definition: SIM_Gimbal.h:64
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
mavlink_message_t rxmsg
Definition: SIM_Gimbal.h:100
Vector3f joint_angles
Definition: SIM_Gimbal.h:55
Vector3f gimbal_angular_rate
Definition: SIM_Gimbal.h:44
Matrix3f dcm
Definition: SIM_Gimbal.h:38
const uint16_t target_port
Definition: SIM_Gimbal.h:35
bool seen_gimbal_control
Definition: SIM_Gimbal.h:92
bool connected
Definition: SIM_Gimbal.h:99
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
Vector3f supplied_gyro_bias
Definition: SIM_Gimbal.h:87
const float travelLimitGain
Definition: SIM_Gimbal.h:61
uint32_t last_heartbeat_ms
Definition: SIM_Gimbal.h:90
const char * target_address
Definition: SIM_Gimbal.h:34
uint32_t last_report_us
Definition: SIM_Gimbal.h:89
mavlink_status_t status
Definition: SIM_Gimbal.h:101
Vector3f delta_angle
Definition: SIM_Gimbal.h:73
struct SITL::Gimbal::@203 mavlink
uint8_t seq
Definition: SIM_Gimbal.h:102
const float reporting_period_ms
Definition: SIM_Gimbal.h:70
Vector3f demanded_angular_rate
Definition: SIM_Gimbal.h:82
Vector3f gyro
Definition: SIM_Gimbal.h:47
uint8_t vehicle_component_id
Definition: SIM_Gimbal.h:94