SIM_Gimbal.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. gimbal simulator class for MAVLink gimbal
  15. */
  16. #include "SIM_Gimbal.h"
  17. #include <stdio.h>
  18. #include "SIM_Aircraft.h"
  19. #include <AP_InertialSensor/AP_InertialSensor.h>
  20. extern const AP_HAL::HAL& hal;
  21. namespace SITL {
  22. Gimbal::Gimbal(const struct sitl_fdm &_fdm) :
  23. fdm(_fdm),
  24. target_address("127.0.0.1"),
  25. target_port(5762),
  26. lower_joint_limits(radians(-40), radians(-135), radians(-7.5)),
  27. upper_joint_limits(radians(40), radians(45), radians(7.5)),
  28. travelLimitGain(20),
  29. reporting_period_ms(10),
  30. seen_heartbeat(false),
  31. seen_gimbal_control(false),
  32. mav_socket(false)
  33. {
  34. memset(&mavlink, 0, sizeof(mavlink));
  35. fdm.quaternion.rotation_matrix(dcm);
  36. }
  37. /*
  38. update the gimbal state
  39. */
  40. void Gimbal::update(void)
  41. {
  42. // calculate delta time in seconds
  43. uint32_t now_us = AP_HAL::micros();
  44. float delta_t = (now_us - last_update_us) * 1.0e-6f;
  45. last_update_us = now_us;
  46. Matrix3f vehicle_dcm;
  47. fdm.quaternion.rotation_matrix(vehicle_dcm);
  48. const Vector3f &vehicle_gyro = AP::ins().get_gyro();
  49. const Vector3f &vehicle_accel_body = AP::ins().get_accel();
  50. // take a copy of the demanded rates to bypass the limiter function for testing
  51. Vector3f demRateRaw = demanded_angular_rate;
  52. // 1) Rotate the copters rotation rates into the gimbals frame of reference
  53. // copterAngRate_G = transpose(DCMgimbal)*DCMcopter*copterAngRate
  54. Vector3f copterAngRate_G = dcm.transposed()*vehicle_dcm*vehicle_gyro;
  55. // 2) Subtract the copters body rates to obtain a copter relative rotational
  56. // rate vector (X,Y,Z) in gimbal sensor frame
  57. // relativeGimbalRate(X,Y,Z) = gimbalRateDemand - copterAngRate_G
  58. Vector3f relativeGimbalRate = demanded_angular_rate - copterAngRate_G;
  59. // calculate joint angles (euler312 order)
  60. // calculate copter -> gimbal rotation matrix
  61. Matrix3f rotmat_copter_gimbal = dcm.transposed() * vehicle_dcm;
  62. joint_angles = rotmat_copter_gimbal.transposed().to_euler312();
  63. /* 4) For each of the three joints, calculate upper and lower rate limits
  64. from the corresponding angle limits and current joint angles
  65. upperRatelimit = (jointAngle - lowerAngleLimit) * travelLimitGain
  66. lowerRatelimit = (jointAngle - upperAngleLimit) * travelLimitGain
  67. travelLimitGain is equal to the inverse of the bump stop time constant and
  68. should be set to something like 20 initially. If set too high it can cause
  69. the rates to 'ring' when they the limiter is in force, particularly given
  70. we are using a first order numerical integration.
  71. */
  72. Vector3f upperRatelimit = -(joint_angles - upper_joint_limits) * travelLimitGain;
  73. Vector3f lowerRatelimit = -(joint_angles - lower_joint_limits) * travelLimitGain;
  74. /*
  75. 5) Calculate the gimbal joint rates (roll, elevation, azimuth)
  76. gimbalJointRates(roll, elev, azimuth) = Matrix*relativeGimbalRate(X,Y,Z)
  77. where matrix =
  78. +- -+
  79. | cos(elevAngle), 0, sin(elevAngle) |
  80. | |
  81. | sin(elevAngle) tan(rollAngle), 1, -cos(elevAngle) tan(rollAngle) |
  82. | |
  83. | sin(elevAngle) cos(elevAngle) |
  84. | - --------------, 0, -------------- |
  85. | cos(rollAngle) cos(rollAngle) |
  86. +- -+
  87. */
  88. float rollAngle = joint_angles.x;
  89. float elevAngle = joint_angles.y;
  90. Matrix3f matrix = Matrix3f(Vector3f(cosf(elevAngle), 0, sinf(elevAngle)),
  91. Vector3f(sinf(elevAngle)*tanf(rollAngle), 1, -cosf(elevAngle)*tanf(rollAngle)),
  92. Vector3f(-sinf(elevAngle)/cosf(rollAngle), 0, cosf(elevAngle)/cosf(rollAngle)));
  93. Vector3f gimbalJointRates = matrix * relativeGimbalRate;
  94. // 6) Apply the rate limits from 4)
  95. gimbalJointRates.x = constrain_float(gimbalJointRates.x, lowerRatelimit.x, upperRatelimit.x);
  96. gimbalJointRates.y = constrain_float(gimbalJointRates.y, lowerRatelimit.y, upperRatelimit.y);
  97. gimbalJointRates.z = constrain_float(gimbalJointRates.z, lowerRatelimit.z, upperRatelimit.z);
  98. /*
  99. 7) Convert the modified gimbal joint rates to body rates (still copter
  100. relative)
  101. relativeGimbalRate(X,Y,Z) = Matrix * gimbalJointRates(roll, elev, azimuth)
  102. where Matrix =
  103. +- -+
  104. | cos(elevAngle), 0, -cos(rollAngle) sin(elevAngle) |
  105. | |
  106. | 0, 1, sin(rollAngle) |
  107. | |
  108. | sin(elevAngle), 0, cos(elevAngle) cos(rollAngle) |
  109. +- -+
  110. */
  111. matrix = Matrix3f(Vector3f(cosf(elevAngle), 0, -cosf(rollAngle)*sinf(elevAngle)),
  112. Vector3f(0, 1, sinf(rollAngle)),
  113. Vector3f(sinf(elevAngle), 0, cosf(elevAngle)*cosf(rollAngle)));
  114. relativeGimbalRate = matrix * gimbalJointRates;
  115. // 8) Add to the result from step 1) to obtain the demanded gimbal body rates
  116. // in an inertial frame of reference
  117. // demandedGimbalRatesInertial(X,Y,Z) = relativeGimbalRate(X,Y,Z) + copterAngRate_G
  118. // Vector3f demandedGimbalRatesInertial = relativeGimbalRate + copterAngRate_G;
  119. // for the moment we will set gyros equal to demanded_angular_rate
  120. gimbal_angular_rate = demRateRaw; // demandedGimbalRatesInertial + true_gyro_bias - supplied_gyro_bias
  121. // update rotation of the gimbal
  122. dcm.rotate(gimbal_angular_rate*delta_t);
  123. dcm.normalize();
  124. // calculate copter -> gimbal rotation matrix
  125. rotmat_copter_gimbal = dcm.transposed() * vehicle_dcm;
  126. // calculate joint angles (euler312 order)
  127. joint_angles = rotmat_copter_gimbal.transposed().to_euler312();
  128. // update observed gyro
  129. gyro = gimbal_angular_rate + true_gyro_bias;
  130. // update delta_angle (integrate)
  131. delta_angle += gyro * delta_t;
  132. // calculate accel in gimbal body frame
  133. Vector3f copter_accel_earth = vehicle_dcm * vehicle_accel_body;
  134. Vector3f accel = dcm.transposed() * copter_accel_earth;
  135. // integrate velocity
  136. delta_velocity += accel * delta_t;
  137. // see if we should do a report
  138. send_report();
  139. }
  140. static struct gimbal_param {
  141. const char *name;
  142. float value;
  143. } gimbal_params[] = {
  144. {"GMB_OFF_ACC_X", 0},
  145. {"GMB_OFF_ACC_Y", 0},
  146. {"GMB_OFF_ACC_Z", 0},
  147. {"GMB_GN_ACC_X", 0},
  148. {"GMB_GN_ACC_Y", 0},
  149. {"GMB_GN_ACC_Z", 0},
  150. {"GMB_OFF_GYRO_X", 0},
  151. {"GMB_OFF_GYRO_Y", 0},
  152. {"GMB_OFF_GYRO_Z", 0},
  153. {"GMB_OFF_JNT_X", 0},
  154. {"GMB_OFF_JNT_Y", 0},
  155. {"GMB_OFF_JNT_Z", 0},
  156. {"GMB_K_RATE", 0},
  157. {"GMB_POS_HOLD", 0},
  158. {"GMB_MAX_TORQUE", 0},
  159. {"GMB_SND_TORQUE", 0},
  160. {"GMB_SYSID", 0},
  161. {"GMB_FLASH", 0},
  162. };
  163. /*
  164. find a parameter structure
  165. */
  166. struct gimbal_param *Gimbal::param_find(const char *name)
  167. {
  168. for (uint8_t i=0; i<ARRAY_SIZE(gimbal_params); i++) {
  169. if (strncmp(name, gimbal_params[i].name, 16) == 0) {
  170. return &gimbal_params[i];
  171. }
  172. }
  173. return nullptr;
  174. }
  175. /*
  176. send a parameter to flight board
  177. */
  178. void Gimbal::param_send(const struct gimbal_param *p)
  179. {
  180. mavlink_message_t msg;
  181. mavlink_param_value_t param_value;
  182. strncpy(param_value.param_id, p->name, sizeof(param_value.param_id));
  183. param_value.param_value = p->value;
  184. param_value.param_count = 0;
  185. param_value.param_index = 0;
  186. param_value.param_type = MAV_PARAM_TYPE_REAL32;
  187. mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
  188. uint8_t saved_seq = chan0_status->current_tx_seq;
  189. chan0_status->current_tx_seq = mavlink.seq;
  190. uint16_t len = mavlink_msg_param_value_encode(vehicle_system_id,
  191. vehicle_component_id,
  192. &msg, &param_value);
  193. chan0_status->current_tx_seq = saved_seq;
  194. uint8_t msgbuf[len];
  195. len = mavlink_msg_to_send_buffer(msgbuf, &msg);
  196. if (len > 0) {
  197. mav_socket.send(msgbuf, len);
  198. }
  199. }
  200. /*
  201. send a report to the vehicle control code over MAVLink
  202. */
  203. void Gimbal::send_report(void)
  204. {
  205. uint32_t now = AP_HAL::millis();
  206. if (now < 10000) {
  207. // don't send gimbal reports until 10s after startup. This
  208. // avoids a windows threading issue with non-blocking sockets
  209. // and the initial wait on uartA
  210. return;
  211. }
  212. if (!mavlink.connected && mav_socket.connect(target_address, target_port)) {
  213. ::printf("Gimbal connected to %s:%u\n", target_address, (unsigned)target_port);
  214. mavlink.connected = true;
  215. }
  216. if (!mavlink.connected) {
  217. return;
  218. }
  219. if (param_send_last_ms && now - param_send_last_ms > 100) {
  220. param_send(&gimbal_params[param_send_idx]);
  221. if (++param_send_idx == ARRAY_SIZE(gimbal_params)) {
  222. printf("Finished sending parameters\n");
  223. param_send_last_ms = 0;
  224. }
  225. }
  226. // check for incoming MAVLink messages
  227. uint8_t buf[100];
  228. ssize_t ret;
  229. while ((ret=mav_socket.recv(buf, sizeof(buf), 0)) > 0) {
  230. for (uint8_t i=0; i<ret; i++) {
  231. mavlink_message_t msg;
  232. mavlink_status_t status;
  233. if (mavlink_frame_char_buffer(&mavlink.rxmsg, &mavlink.status,
  234. buf[i],
  235. &msg, &status) == MAVLINK_FRAMING_OK) {
  236. switch (msg.msgid) {
  237. case MAVLINK_MSG_ID_HEARTBEAT: {
  238. mavlink_heartbeat_t pkt;
  239. mavlink_msg_heartbeat_decode(&msg, &pkt);
  240. printf("Gimbal: got HB type=%u autopilot=%u base_mode=0x%x\n", pkt.type, pkt.autopilot, pkt.base_mode);
  241. if (!seen_heartbeat) {
  242. seen_heartbeat = true;
  243. vehicle_component_id = msg.compid;
  244. vehicle_system_id = msg.sysid;
  245. ::printf("Gimbal using srcSystem %u\n", (unsigned)vehicle_system_id);
  246. }
  247. break;
  248. }
  249. case MAVLINK_MSG_ID_GIMBAL_CONTROL: {
  250. static uint32_t counter;
  251. if (counter++ % 100 == 0) {
  252. printf("GIMBAL_CONTROL %u\n", counter);
  253. }
  254. mavlink_gimbal_control_t pkt;
  255. mavlink_msg_gimbal_control_decode(&msg, &pkt);
  256. demanded_angular_rate = Vector3f(pkt.demanded_rate_x,
  257. pkt.demanded_rate_y,
  258. pkt.demanded_rate_z);
  259. // no longer supply a bias
  260. supplied_gyro_bias.zero();
  261. seen_gimbal_control = true;
  262. break;
  263. }
  264. case MAVLINK_MSG_ID_PARAM_SET: {
  265. mavlink_param_set_t pkt;
  266. mavlink_msg_param_set_decode(&msg, &pkt);
  267. printf("Gimbal got PARAM_SET %.16s %f\n", pkt.param_id, pkt.param_value);
  268. struct gimbal_param *p = param_find(pkt.param_id);
  269. if (p) {
  270. p->value = pkt.param_value;
  271. param_send(p);
  272. }
  273. break;
  274. }
  275. case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
  276. mavlink_param_request_list_t pkt;
  277. mavlink_msg_param_request_list_decode(&msg, &pkt);
  278. if (pkt.target_system == 0 && pkt.target_component == MAV_COMP_ID_GIMBAL) {
  279. // start param send
  280. param_send_idx = 0;
  281. param_send_last_ms = AP_HAL::millis();
  282. }
  283. printf("Gimbal sending %u parameters\n", (unsigned)ARRAY_SIZE(gimbal_params));
  284. break;
  285. }
  286. default:
  287. printf("Gimbal got unexpected msg %u\n", msg.msgid);
  288. break;
  289. }
  290. }
  291. }
  292. }
  293. if (!seen_heartbeat) {
  294. return;
  295. }
  296. mavlink_message_t msg;
  297. uint16_t len;
  298. if (now - last_heartbeat_ms >= 1000) {
  299. mavlink_heartbeat_t heartbeat;
  300. heartbeat.type = MAV_TYPE_GIMBAL;
  301. heartbeat.autopilot = MAV_AUTOPILOT_ARDUPILOTMEGA;
  302. heartbeat.base_mode = 0;
  303. heartbeat.system_status = 0;
  304. heartbeat.mavlink_version = 0;
  305. heartbeat.custom_mode = 0;
  306. /*
  307. save and restore sequence number for chan0, as it is used by
  308. generated encode functions
  309. */
  310. mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
  311. uint8_t saved_seq = chan0_status->current_tx_seq;
  312. chan0_status->current_tx_seq = mavlink.seq;
  313. len = mavlink_msg_heartbeat_encode(vehicle_system_id,
  314. vehicle_component_id,
  315. &msg, &heartbeat);
  316. chan0_status->current_tx_seq = saved_seq;
  317. mav_socket.send(&msg.magic, len);
  318. last_heartbeat_ms = now;
  319. }
  320. /*
  321. send a GIMBAL_REPORT message
  322. */
  323. uint32_t now_us = AP_HAL::micros();
  324. if (now_us - last_report_us > reporting_period_ms*1000UL) {
  325. mavlink_gimbal_report_t gimbal_report;
  326. float delta_time = (now_us - last_report_us) * 1.0e-6f;
  327. last_report_us = now_us;
  328. gimbal_report.target_system = vehicle_system_id;
  329. gimbal_report.target_component = vehicle_component_id;
  330. gimbal_report.delta_time = delta_time;
  331. gimbal_report.delta_angle_x = delta_angle.x;
  332. gimbal_report.delta_angle_y = delta_angle.y;
  333. gimbal_report.delta_angle_z = delta_angle.z;
  334. gimbal_report.delta_velocity_x = delta_velocity.x;
  335. gimbal_report.delta_velocity_y = delta_velocity.y;
  336. gimbal_report.delta_velocity_z = delta_velocity.z;
  337. gimbal_report.joint_roll = joint_angles.x;
  338. gimbal_report.joint_el = joint_angles.y;
  339. gimbal_report.joint_az = joint_angles.z;
  340. mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
  341. uint8_t saved_seq = chan0_status->current_tx_seq;
  342. chan0_status->current_tx_seq = mavlink.seq;
  343. len = mavlink_msg_gimbal_report_encode(vehicle_system_id,
  344. vehicle_component_id,
  345. &msg, &gimbal_report);
  346. chan0_status->current_tx_seq = saved_seq;
  347. uint8_t msgbuf[len];
  348. len = mavlink_msg_to_send_buffer(msgbuf, &msg);
  349. if (len > 0) {
  350. mav_socket.send(msgbuf, len);
  351. }
  352. delta_velocity.zero();
  353. delta_angle.zero();
  354. }
  355. }
  356. } // namespace SITL