Skip to content

Commit a5812a8

Browse files
ReladormAndrypeterbarker
authored andcommitted
Added support for version 2 protocol generation for Ada.
Added MAVDeprecated class to mavparse.py Added deprecated field to MAVType, MAVEnumEntry, MAVEnum classes that are filled from the XML specification to generate corresponding comments. Added invalid field to MAVField class that is filled from XML specification and can be used in generation. For example, to set as an initial (non-initialized) value for the field.
1 parent b684ea5 commit a5812a8

24 files changed

+3982
-446
lines changed
Lines changed: 43 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -1,57 +1,76 @@
1-
-- Connects to ardupilot (baud rate 115200) via ttyUSB0 and read all params
2-
-- Copyright Fil Andrii root.fi36@gmail.com 2022s
1+
-- Connects to ardupilot (baud rate 115200) via ttyUSB0 and read all params
2+
-- Copyright Fil Andrii root.fi36@gmail.com 2022s
33

4+
pragma Ada_2022;
5+
6+
with Ada.Numerics.Generic_Elementary_Functions;
47
with Ada.Streams;
5-
with GNAT.Serial_Communications;
68
with Ada.Text_IO;
9+
10+
with GNAT.Serial_Communications;
711
with Interfaces;
8-
with Ada.Numerics.Generic_Elementary_Functions;
912

10-
with Mavlink;
11-
with Mavlink.Connection;
12-
with Mavlink.Messages;
13-
with Mavlink.Types;
13+
with MAVLink.V1;
14+
with MAVLink.V1.Common.Attitudes;
1415

1516
procedure Attitude is
1617
use type Ada.Streams.Stream_Element_Offset;
1718
use type Interfaces.Unsigned_8;
18-
package Short_Float_Text_IO is new Ada.Text_IO.Float_IO(Short_Float);
19+
use type Interfaces.IEEE_Float_32;
1920

20-
Ser : GNAT.Serial_Communications.Serial_Port;
21-
Input : Ada.Streams.Stream_Element_Array(1..1024);
21+
package IEEE_Text_IO is new Ada.Text_IO.Float_IO (Interfaces.IEEE_Float_32);
22+
23+
Ser : GNAT.Serial_Communications.Serial_Port;
24+
Input : Ada.Streams.Stream_Element_Array(1 .. 1024);
2225
Input_Last : Ada.Streams.Stream_Element_Offset;
2326

24-
Mav_Conn : Mavlink.Connection.Connection (System_Id => 250);
27+
Mav_Conn : MAVLink.V1.Connection;
2528

2629
procedure Handler_Attitude is
27-
Attitude : Mavlink.Messages.Attitude;
28-
K_Rad2Deg : Short_Float := 180.0 / Ada.Numerics.Pi;
30+
Attitude : MAVLink.V1.Common.Attitudes.Attitude;
31+
K_Rad2Deg : Interfaces.IEEE_Float_32 := 180.0 / Ada.Numerics.Pi;
2932
begin
30-
Mav_Conn.Unpack (Attitude);
33+
pragma Assert (MAVLink.V1.Common.Attitudes.Check_CRC (Mav_Conn));
34+
35+
MAVLink.V1.Common.Attitudes.Decode (Attitude, Mav_Conn);
3136

3237
Ada.Text_IO.Put ("Pitch: ");
33-
Short_Float_Text_IO.Put(Attitude.Pitch * K_Rad2Deg, Aft => 4, Exp => 0);
38+
IEEE_Text_IO.Put (Attitude.Pitch * K_Rad2Deg, Aft => 4, Exp => 0);
3439
Ada.Text_IO.Put (" Roll: ");
35-
Short_Float_Text_IO.Put(Attitude.Roll * K_Rad2Deg, Aft => 4, Exp => 0);
40+
IEEE_Text_IO.Put (Attitude.Roll * K_Rad2Deg, Aft => 4, Exp => 0);
3641
Ada.Text_IO.Put (" Yaw: ");
37-
Short_Float_Text_IO.Put(Attitude.Yaw * K_Rad2Deg, Aft => 4, Exp => 0);
42+
IEEE_Text_IO.Put (Attitude.Yaw * K_Rad2Deg, Aft => 4, Exp => 0);
3843
Ada.Text_IO.New_Line;
3944
end Handler_Attitude;
4045

4146
begin
42-
Ada.Text_IO.Put_Line ("Connects to ardupilot (baud rate 115200) via ttyUSB0 and reads attitude angles");
47+
MAVLink.V1.Set_System_Id (Mav_Conn, 250);
48+
MAVLink.V1.Set_Component_Id (Mav_Conn, 1);
49+
50+
Ada.Text_IO.Put_Line
51+
("Connects to ardupilot (baud rate 115200) via "
52+
& "ttyUSB0 and reads attitude angles");
4353

4454
GNAT.Serial_Communications.Open (Port => Ser, Name => "/dev/ttyUSB0");
45-
GNAT.Serial_Communications.Set (Port => Ser, Rate => GNAT.Serial_Communications.B115200, Block => True, Timeout => 0.0);
55+
56+
GNAT.Serial_Communications.Set
57+
(Port => Ser,
58+
Rate => GNAT.Serial_Communications.B115200,
59+
Block => True,
60+
Timeout => 0.0);
4661

4762
loop
48-
GNAT.Serial_Communications.Read (Port => Ser, Buffer => Input, Last => Input_Last);
63+
GNAT.Serial_Communications.Read
64+
(Port => Ser, Buffer => Input, Last => Input_Last);
65+
4966
for B of Input (Input'First .. Input_Last) loop
50-
if Mav_Conn.Parse_Byte(Interfaces.Unsigned_8(B)) then
51-
if Mav_Conn.Get_Msg_Id = Mavlink.Messages.Attitude_Id then
67+
if MAVLink.V1.Parse_Byte (Mav_Conn, Interfaces.Unsigned_8 (B)) then
68+
if MAVLink.V1.Get_Msg_Id (Mav_Conn) =
69+
MAVLink.V1.Common.Attitude_Id
70+
then
5271
Handler_Attitude;
5372
end if;
5473
end if;
5574
end loop;
5675
end loop;
57-
end Attitude;
76+
end Attitude;

generator/Ada/examples/make.sh

100644100755
Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,6 @@
22

33
mkdir build
44

5-
gnatmake -a --create-missing-dirs attitude.adb -D build -I..
6-
gnatmake -a --create-missing-dirs param_request_list.adb -D build -I..
7-
gnatmake -a --create-missing-dirs param_set_sr0_params -D build -I..
5+
gnatmake -gnat2022 -a --create-missing-dirs attitude.adb -D build -I..
6+
gnatmake -gnat2022 -a --create-missing-dirs param_request_list.adb -D build -I..
7+
gnatmake -gnat2022 -a --create-missing-dirs param_set_sr0_params -D build -I..
Lines changed: 61 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -1,67 +1,96 @@
1-
-- Connects to ardupilot (baud rate 115200) via ttyUSB0 and read all params
2-
-- Copyright Fil Andrii root.fi36@gmail.com 2022
1+
-- Connects to ardupilot (baud rate 115200) via ttyUSB0 and read all params
2+
-- Copyright Fil Andrii root.fi36@gmail.com 2022
3+
4+
pragma Ada_2022;
35

4-
with Ada.Streams;
5-
with GNAT.Serial_Communications;
6-
with Ada.Text_IO;
7-
with Interfaces;
86
with Ada.Numerics.Generic_Elementary_Functions;
97
with Ada.Strings;
108
with Ada.Strings.Fixed;
119
with Ada.Strings.Maps;
10+
with Ada.Streams;
11+
with Ada.Text_IO;
12+
13+
with GNAT.Serial_Communications;
14+
with Interfaces;
1215

13-
with Mavlink;
14-
with Mavlink.Connection;
15-
with Mavlink.Messages;
16-
with Mavlink.Types;
16+
with MAVLink.V1;
17+
with MAVLink.V1.Common.Param_Request_Lists;
18+
with MAVLink.V1.Common.Param_Values;
1719

1820
procedure Param_Request_List is
1921
use type Ada.Streams.Stream_Element_Offset;
2022
use type Interfaces.Unsigned_8;
21-
package Short_Float_Text_IO is new Ada.Text_IO.Float_IO(Short_Float);
23+
use type Interfaces.IEEE_Float_32;
24+
25+
package IEEE_Text_IO is new Ada.Text_IO.Float_IO (Interfaces.IEEE_Float_32);
2226

23-
Ser : GNAT.Serial_Communications.Serial_Port;
24-
Input : Ada.Streams.Stream_Element_Array(1..1024);
25-
Input_Last : Ada.Streams.Stream_Element_Offset;
26-
Output : Ada.Streams.Stream_Element_Array(1..1024);
27-
Output_Last : Ada.Streams.Stream_Element_Offset := Output'First;
27+
Ser : GNAT.Serial_Communications.Serial_Port;
28+
Input : Ada.Streams.Stream_Element_Array (1 .. 1024);
29+
Input_Last : Ada.Streams.Stream_Element_Offset;
30+
Output : MAVLink.V1.Data_Buffer (1 .. 1024);
31+
Output_Last : Natural := Output'First;
2832

29-
Mav_Conn : Mavlink.Connection.Connection (System_Id => 250);
33+
Mav_Conn : MAVLink.V1.Connection;
3034

3135
procedure Handler_Param_Value is
32-
Param_Value : Mavlink.Messages.Param_Value;
36+
Param_Value : MAVLink.V1.Common.Param_Values.Param_Value;
3337
begin
34-
Mav_Conn.Unpack (Param_Value);
38+
pragma Assert
39+
(MAVLink.V1.Common.Param_Values.Check_CRC (Mav_Conn));
40+
41+
MAVLink.V1.Common.Param_Values.Decode (Param_Value, Mav_Conn);
3542
Ada.Text_IO.Put (Param_Value.Param_Id & " = ");
36-
Short_Float_Text_IO.Put (Param_Value.Param_Value, Aft => 4, Exp => 0);
43+
IEEE_Text_IO.Put (Param_Value.Param_Value, Aft => 4, Exp => 0);
3744
Ada.Text_IO.New_Line;
3845
end Handler_Param_Value;
3946

40-
Param_Request_List : Mavlink.Messages.Param_Request_List;
47+
Param_Request_List : MAVLink.V1.Common.
48+
Param_Request_Lists.Param_Request_List;
4149

4250
begin
43-
Ada.Text_IO.Put_Line ("Connects to ardupilot (baud rate 115200) via ttyUSB0 and read all params");
51+
MAVLink.V1.Set_System_Id (Mav_Conn, 250);
52+
MAVLink.V1.Set_Component_Id (Mav_Conn, 1);
53+
54+
Ada.Text_IO.Put_Line
55+
("Connects to ardupilot (baud rate 115200) via"
56+
& " ttyUSB0 and read all params");
4457

4558
GNAT.Serial_Communications.Open (Port => Ser, Name => "/dev/ttyUSB0");
46-
GNAT.Serial_Communications.Set (Port => Ser, Rate => GNAT.Serial_Communications.B115200, Block => True, Timeout => 0.0);
59+
60+
GNAT.Serial_Communications.Set
61+
(Port => Ser,
62+
Rate => GNAT.Serial_Communications.B115200,
63+
Block => True, Timeout => 0.0);
4764

4865
Param_Request_List.Target_System := 1;
4966
Param_Request_List.Target_Component := 0;
5067

51-
for B of Mav_Conn.Pack (Param_Request_List) loop
52-
Output (Output_Last) := Ada.Streams.Stream_Element (B);
53-
Output_Last := Output_Last + 1;
54-
end loop;
55-
GNAT.Serial_Communications.Write (Port => Ser, Buffer => Output (Output'First .. Output_Last));
68+
MAVLink.V1.Common.Param_Request_Lists.Encode
69+
(Param_Request_List, Mav_Conn, Output, Output_Last);
70+
71+
declare
72+
Buffer : Ada.Streams.Stream_Element_Array
73+
(Ada.Streams.Stream_Element_Offset (Output'First) ..
74+
Ada.Streams.Stream_Element_Offset (Output_Last))
75+
with Import, Address => Output'Address;
76+
begin
77+
GNAT.Serial_Communications.Write
78+
(Port => Ser,
79+
Buffer => Buffer);
80+
end;
5681

5782
loop
58-
GNAT.Serial_Communications.Read (Port => Ser, Buffer => Input, Last => Input_Last);
83+
GNAT.Serial_Communications.Read
84+
(Port => Ser, Buffer => Input, Last => Input_Last);
85+
5986
for B of Input (Input'First .. Input_Last) loop
60-
if Mav_Conn.Parse_Byte(Interfaces.Unsigned_8(B)) then
61-
if Mav_Conn.Get_Msg_Id = Mavlink.Messages.Param_Value_Id then
87+
if MAVLink.V1.Parse_Byte (Mav_Conn, Interfaces.Unsigned_8 (B)) then
88+
if MAVLink.V1.Get_Msg_Id (Mav_Conn) =
89+
MAVLink.V1.Common.Param_Value_Id
90+
then
6291
Handler_Param_Value;
6392
end if;
6493
end if;
6594
end loop;
6695
end loop;
67-
end Param_Request_List;
96+
end Param_Request_List;
Lines changed: 74 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -1,80 +1,117 @@
1-
-- Connects to ardupilot (baud rate 115200) via ttyUSB0 and set SR0_PARAMS to 11.
2-
-- Copyright Fil Andrii root.fi36@gmail.com 2022
1+
-- Connects to ardupilot (baud rate 115200) via ttyUSB0 and set SR0_PARAMS to 11.
2+
-- Copyright Fil Andrii root.fi36@gmail.com 2022
3+
4+
pragma Ada_2022;
35

4-
with Ada.Streams;
5-
with GNAT.Serial_Communications;
6-
with Ada.Text_IO;
7-
with Interfaces;
86
with Ada.Numerics.Generic_Elementary_Functions;
97
with Ada.Strings;
108
with Ada.Strings.Fixed;
119
with Ada.Strings.Maps;
10+
with Ada.Streams;
11+
with Ada.Text_IO;
12+
13+
with GNAT.Serial_Communications;
14+
with Interfaces;
1215

13-
with Mavlink;
14-
with Mavlink.Connection;
15-
with Mavlink.Messages;
16-
with Mavlink.Types;
16+
with MAVLink.V1.Common.Types;
17+
with MAVLink.V1.Common.Param_Sets;
18+
with MAVLink.V1.Common.Param_Values;
1719

1820
procedure Param_Set_SR0_PARAMS is
1921
use type Ada.Streams.Stream_Element_Offset;
2022
use type Interfaces.Unsigned_8;
21-
package Short_Float_Text_IO is new Ada.Text_IO.Float_IO(Short_Float);
23+
use type Interfaces.IEEE_Float_32;
24+
25+
package IEEE_Text_IO is new Ada.Text_IO.Float_IO (Interfaces.IEEE_Float_32);
2226

23-
Ser : GNAT.Serial_Communications.Serial_Port;
24-
Input : Ada.Streams.Stream_Element_Array(1..1024);
25-
Input_Last : Ada.Streams.Stream_Element_Offset;
26-
Output : Ada.Streams.Stream_Element_Array(1..1024);
27-
Output_Last : Ada.Streams.Stream_Element_Offset := Output'First;
27+
Ser : GNAT.Serial_Communications.Serial_Port;
28+
Input : Ada.Streams.Stream_Element_Array (1 .. 1024);
29+
Input_Last : Ada.Streams.Stream_Element_Offset;
30+
Output : MAVLink.V1.Data_Buffer (1 .. 1024);
31+
Output_Last : Natural := Output'First;
2832

29-
Mav_Conn : Mavlink.Connection.Connection (System_Id => 250);
33+
Mav_Conn : MAVLink.V1.Connection;
3034

3135
function Handler_Param_Value return Boolean is
32-
Param_Value : Mavlink.Messages.Param_Value;
36+
Param_Value : MAVLink.V1.Common.Param_Values.Param_Value;
3337
begin
34-
Mav_Conn.Unpack (Param_Value);
35-
if Ada.Strings.Fixed.Trim (Source => Param_Value.Param_Id,
36-
Left => Ada.Strings.Maps.Null_Set,
37-
Right => Ada.Strings.Maps.To_Set (ASCII.Nul)) = "SR0_PARAMS" then
38+
pragma Assert
39+
(MAVLink.V1.Common.Param_Values.Check_CRC (Mav_Conn));
40+
41+
MAVLink.V1.Common.Param_Values.Decode (Param_Value, Mav_Conn);
42+
43+
if Ada.Strings.Fixed.Trim
44+
(Source => Param_Value.Param_Id,
45+
Left => Ada.Strings.Maps.Null_Set,
46+
Right => Ada.Strings.Maps.To_Set (ASCII.Nul)) = "SR0_PARAMS"
47+
then
3848
Ada.Text_IO.Put (Param_Value.Param_Id & " = ");
39-
Short_Float_Text_IO.Put (Param_Value.Param_Value, Aft => 4, Exp => 0);
49+
IEEE_Text_IO.Put (Param_Value.Param_Value, Aft => 4, Exp => 0);
4050
Ada.Text_IO.New_Line;
4151

4252
return True;
4353
end if;
4454
return False;
4555
end Handler_Param_Value;
4656

47-
Param_Set : Mavlink.Messages.Param_Set;
57+
Param_Set : MAVLink.V1.Common.Param_Sets.Param_Set;
4858

4959
begin
50-
Ada.Text_IO.Put_Line ("Connects to ardupilot (baud rate 115200) via ttyUSB0 and set SR0_PARAMS to 11.");
60+
MAVLink.V1.Set_System_Id (Mav_Conn, 250);
61+
MAVLink.V1.Set_Component_Id (Mav_Conn, 1);
62+
63+
Ada.Text_IO.Put_Line
64+
("Connects to ardupilot (baud rate 115200) via "
65+
& "ttyUSB0 and set SR0_PARAMS to 11.");
5166
Ada.Text_IO.Put_Line ("Warning this app change param SR0_PARAMS to 11!");
5267

5368
GNAT.Serial_Communications.Open (Port => Ser, Name => "/dev/ttyUSB0");
54-
GNAT.Serial_Communications.Set (Port => Ser, Rate => GNAT.Serial_Communications.B115200, Block => True, Timeout => 0.0);
69+
70+
GNAT.Serial_Communications.Set
71+
(Port => Ser,
72+
Rate => GNAT.Serial_Communications.B115200,
73+
Block => True,
74+
Timeout => 0.0);
5575

5676
Param_Set.Target_System := 1;
5777
Param_Set.Target_Component := 0;
58-
Param_Set.Param_Id := Ada.Strings.Fixed.Head(Source => "SR0_PARAMS", Count => 16, Pad => ASCII.Nul);
78+
Param_Set.Param_Id := Ada.Strings.Fixed.Head
79+
(Source => "SR0_PARAMS",
80+
Count => 16,
81+
Pad => ASCII.Nul);
5982
Param_Set.Param_Value := 11.0;
60-
Param_Set.Param_Type := Mavlink.Types.Mav_Param_Type_Real32;
83+
Param_Set.Param_Type := MAVLink.V1.Common.Types.Real32;
84+
85+
MAVLink.V1.Common.Param_Sets.Encode
86+
(Param_Set, Mav_Conn, Output, Output_Last);
6187

62-
for B of Mav_Conn.Pack (Param_Set) loop
63-
Output (Output_Last) := Ada.Streams.Stream_Element (B);
64-
Output_Last := Output_Last + 1;
65-
end loop;
66-
GNAT.Serial_Communications.Write (Port => Ser, Buffer => Output (Output'First .. Output_Last));
88+
declare
89+
Buffer : Ada.Streams.Stream_Element_Array
90+
(Ada.Streams.Stream_Element_Offset (Output'First) ..
91+
Ada.Streams.Stream_Element_Offset (Output_Last))
92+
with Import, Address => Output'Address;
93+
begin
94+
GNAT.Serial_Communications.Write
95+
(Port => Ser,
96+
Buffer => Buffer);
97+
end;
6798

6899
Main_Loop: loop
69-
GNAT.Serial_Communications.Read (Port => Ser, Buffer => Input, Last => Input_Last);
100+
GNAT.Serial_Communications.Read
101+
(Port => Ser,
102+
Buffer => Input,
103+
Last => Input_Last);
104+
70105
for B of Input (Input'First .. Input_Last) loop
71-
if Mav_Conn.Parse_Byte(Interfaces.Unsigned_8(B)) then
72-
if Mav_Conn.Get_Msg_Id = Mavlink.Messages.Param_Value_Id then
106+
if MAVLink.V1.Parse_Byte(Mav_Conn, Interfaces.Unsigned_8 (B)) then
107+
if MAVLink.V1.Get_Msg_Id (Mav_Conn) =
108+
MAVLink.V1.Common.Param_Value_Id
109+
then
73110
if Handler_Param_Value then
74111
exit Main_Loop;
75112
end if;
76113
end if;
77114
end if;
78115
end loop;
79116
end loop Main_Loop;
80-
end Param_Set_SR0_PARAMS;
117+
end Param_Set_SR0_PARAMS;

0 commit comments

Comments
 (0)