message.js 8.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252
  1. var mavlink = require('../implementations/mavlink_common_v1.0/mavlink.js'),
  2. should = require('should');
  3. describe('MAVLink message registry', function() {
  4. it('defines constructors for every message', function() {
  5. mavlink.messages['gps_raw_int'].should.be.a.function;
  6. });
  7. it('assigns message properties, format with int64 (q), gps_raw_int', function() {
  8. var m = new mavlink.messages['gps_raw_int']();
  9. m.format.should.equal("<QiiiHHHHBB");
  10. m.order_map.should.eql([0, 8, 1, 2, 3, 4, 5, 6, 7, 9]); // should.eql = shallow comparison
  11. m.crc_extra.should.equal(24);
  12. m.id.should.equal(mavlink.MAVLINK_MSG_ID_GPS_RAW_INT);
  13. });
  14. it('assigns message properties, heartbeat', function() {
  15. var m = new mavlink.messages['heartbeat']();
  16. m.format.should.equal("<IBBBBB");
  17. m.order_map.should.eql([1, 2, 3, 0, 4, 5]); // should.eql = shallow comparison
  18. m.crc_extra.should.equal(50);
  19. m.id.should.equal(mavlink.MAVLINK_MSG_ID_HEARTBEAT);
  20. });
  21. });
  22. describe('Complete MAVLink packet', function() {
  23. beforeEach(function() {
  24. this.mav = new MAVLink(null, 42, 150);
  25. });
  26. it('encode gps_raw_int', function() {
  27. // 0x75bcd15 = 123456789
  28. // as long as the number is no bigger than max signed int (2147483648) it can be passed like the following
  29. var gpsraw = new mavlink.messages.gps_raw_int(
  30. time_usec=[123456789, 0]
  31. , fix_type=3
  32. , lat=47123456
  33. , lon=8123456
  34. , alt=50000
  35. , eph=6544
  36. , epv=4566
  37. , vel=1235
  38. , cog=1234
  39. , satellites_visible=9
  40. );
  41. this.mav.seq = 5;
  42. // Create a buffer that matches what the Python version of MAVLink creates
  43. var reference = new Buffer([0xfe, 0x1e, 0x05, 0x2a, 0x96, 0x18, 0x15, 0xcd, 0x5b, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0c, 0xcf, 0x02, 0x40, 0xf4, 0x7b, 0x00, 0x50, 0xc3, 0x00, 0x00, 0x90, 0x19, 0xd6, 0x11, 0xd3, 0x04, 0xd2, 0x04, 0x03, 0x09, 0xee, 0x16]);
  44. new Buffer(gpsraw.pack(this.mav)).should.eql(reference);
  45. });
  46. it('encode gps_raw_int with long integer', function() {
  47. // number ~2^60
  48. // 1152221500606846977 = 0xffd8359 9e3d1801
  49. var gpsraw = new mavlink.messages.gps_raw_int(
  50. time_usec=[0x9e3d1801, 0xffd8359]
  51. , fix_type=3
  52. , lat=47123456
  53. , lon=8123456
  54. , alt=50000
  55. , eph=6544
  56. , epv=4566
  57. , vel=1235
  58. , cog=1234
  59. , satellites_visible=9
  60. );
  61. this.mav.seq = 5;
  62. // Create a buffer that matches what the Python version of MAVLink creates
  63. var reference = new Buffer([0xfe, 0x1e, 0x05, 0x2a, 0x96, 0x18, 0x01, 0x18, 0x3d, 0x9e, 0x59, 0x83, 0xfd, 0x0f, 0x00, 0x0c, 0xcf, 0x02, 0x40, 0xf4, 0x7b, 0x00, 0x50, 0xc3, 0x00, 0x00, 0x90, 0x19, 0xd6, 0x11, 0xd3, 0x04, 0xd2, 0x04, 0x03, 0x09, 0x6c, 0xe8]);
  64. new Buffer(gpsraw.pack(this.mav)).should.eql(reference);
  65. });
  66. it('encode heartbeat', function() {
  67. var heartbeat = new mavlink.messages.heartbeat(
  68. type=5
  69. , autopilot=3
  70. , base_mode=45
  71. , custom_mode=68
  72. , system_status=13
  73. , mavlink_version=1
  74. );
  75. this.mav.seq = 7;
  76. // Create a buffer that matches what the Python version of MAVLink creates
  77. var reference = new Buffer([0xfe, 0x09, 0x07, 0x2a, 0x96, 0x00, 0x44, 0x00, 0x00, 0x00, 0x05, 0x03, 0x2d, 0x0d, 0x01, 0xac, 0x9d]);
  78. new Buffer(heartbeat.pack(this.mav)).should.eql(reference);
  79. });
  80. it('decode gps_raw_int with long integer', function() {
  81. // number ~2^60
  82. // 1152221500606846977 = 0xffd8359 9e3d1801
  83. // Create a buffer that matches what the Python version of MAVLink creates
  84. var reference = new Buffer([0xfe, 0x1e, 0x05, 0x2a, 0x96, 0x18, 0x01, 0x18, 0x3d, 0x9e, 0x59, 0x83, 0xfd, 0x0f, 0x00, 0x0c, 0xcf, 0x02, 0x40, 0xf4, 0x7b, 0x00, 0x50, 0xc3, 0x00, 0x00, 0x90, 0x19, 0xd6, 0x11, 0xd3, 0x04, 0xd2, 0x04, 0x03, 0x09, 0x6c, 0xe8]);
  85. var m = new MAVLink();
  86. var msg = m.parseBuffer(reference);
  87. // check header
  88. msg[0].header.seq.should.eql(5);
  89. msg[0].header.srcSystem.should.eql(42);
  90. msg[0].header.srcComponent.should.eql(150);
  91. // check payload
  92. msg[0].time_usec.should.eql([0x9e3d1801, 0xffd8359, true]);
  93. msg[0].fix_type.should.eql(3);
  94. msg[0].lat.should.eql(47123456);
  95. msg[0].lon.should.eql(8123456);
  96. msg[0].alt.should.eql(50000);
  97. msg[0].eph.should.eql(6544);
  98. msg[0].epv.should.eql(4566);
  99. msg[0].vel.should.eql(1235);
  100. msg[0].cog.should.eql(1234);
  101. msg[0].satellites_visible.should.eql(9);
  102. });
  103. });
  104. describe('MAVLink header', function() {
  105. beforeEach(function() {
  106. this.h = new mavlink.header(mavlink.MAVLINK_MSG_ID_PARAM_REQUEST_LIST, 1, 2, 3, 4);
  107. })
  108. it('Can pack itself', function() {
  109. this.h.pack().should.eql([254, 1, 2, 3, 4, 21]);
  110. });
  111. });
  112. describe('MAVLink message', function() {
  113. beforeEach(function() {
  114. // This is a heartbeat packet from a GCS to the APM.
  115. this.heartbeat = new mavlink.messages.heartbeat(
  116. mavlink.MAV_TYPE_GCS, // 6
  117. mavlink.MAV_AUTOPILOT_INVALID, // 8
  118. 0, // base mode, mavlink.MAV_MODE_FLAG_***
  119. 0, // custom mode
  120. mavlink.MAV_STATE_STANDBY, // system status
  121. 3 // MAVLink version
  122. );
  123. this.mav = new MAVLink(null, 0, 0);
  124. });
  125. it('has a set function to facilitate vivifying the object', function() {
  126. this.heartbeat.type.should.equal(mavlink.MAV_TYPE_GCS);
  127. this.heartbeat.autopilot.should.equal(mavlink.MAV_AUTOPILOT_INVALID);
  128. this.heartbeat.base_mode.should.equal(0);
  129. this.heartbeat.custom_mode.should.equal(0);
  130. this.heartbeat.system_status.should.equal(mavlink.MAV_STATE_STANDBY);
  131. });
  132. // TODO: the length below (9) should perhaps be instead 7. See mavlink.unpack().
  133. // might have to do with the length of the encoding (<I is 4 symbols in the array)
  134. it('Can pack itself', function() {
  135. var packed = this.heartbeat.pack(this.mav);
  136. packed.should.eql([254, 9, 0, 0, 0, mavlink.MAVLINK_MSG_ID_HEARTBEAT, // that bit is the header,
  137. // this is the payload, arranged in the order map specified in the protocol,
  138. // which differs from the constructor.
  139. 0, 0, 0, 0, // custom bitfield -- length 4 (type=I)
  140. mavlink.MAV_TYPE_GCS,
  141. mavlink.MAV_AUTOPILOT_INVALID,
  142. 0,
  143. mavlink.MAV_STATE_STANDBY,
  144. 3,
  145. 109, // CRC
  146. 79 // CRC
  147. ]);
  148. });
  149. describe('decode function', function() {
  150. beforeEach(function() {
  151. this.m = new MAVLink();
  152. });
  153. // need to add tests for the header fields as well, specifying seq etc.
  154. it('Can decode itself', function() {
  155. var packed = this.heartbeat.pack(this.m);
  156. var message = this.m.decode(packed);
  157. // this.fieldnames = ['type', 'autopilot', 'base_mode', 'custom_mode', 'system_status', 'mavlink_version'];
  158. message.type.should.equal(mavlink.MAV_TYPE_GCS); // supposed to be 6
  159. message.autopilot.should.equal(mavlink.MAV_AUTOPILOT_INVALID); // supposed to be 8
  160. message.base_mode.should.equal(0); // supposed to be 0
  161. message.custom_mode.should.equal(0);
  162. message.system_status.should.equal(mavlink.MAV_STATE_STANDBY); // supposed to be 3
  163. message.mavlink_version.should.equal(3); //?
  164. });
  165. it('throws an error if the message has a bad prefix', function() {
  166. var packed = [0, 3, 5, 7, 9, 11]; // bad data prefix in header (0, not 254)
  167. var m = this.m;
  168. (function() { m.decode(packed); }).should.throw('Invalid MAVLink prefix (0)');
  169. });
  170. it('throws an error if the message ID is not known', function() {
  171. var packed = [254, 1, 0, 3, 0, 200, 1, 0, 0]; // 200 = invalid ID
  172. var m = this.m;
  173. (function() { m.decode(packed); }).should.throw('Unknown MAVLink message ID (200)');
  174. });
  175. it('throws an error if the message length is invalid', function() {
  176. var packed = [254, 3, 257, 0, 0, 0, 0, 0];
  177. var m = this.m;
  178. (function() { m.decode(packed); }).should.throw('Invalid MAVLink message length. Got 0 expected 3, msgId=0');
  179. });
  180. it('throws an error if the CRC cannot be unpacked', function() {
  181. });
  182. it('throws an error if the CRC can not be decoded', function() {
  183. });
  184. it('throws an error if it is unable to unpack the payload', function() {
  185. });
  186. it('throws an error if it is unable to instantiate a MAVLink message object from the payload', function() {
  187. });
  188. });
  189. });