@@ -18,6 +18,10 @@ impl<M: mavlink::Message> MAVLinkVehicle<M> {
1818 // Convert from mavlink error to io error
1919 match result {
2020 Err ( mavlink:: error:: MessageWriteError :: Io ( error) ) => Err ( error) ,
21+ Err ( mavlink:: error:: MessageWriteError :: MAVLink2Only ) => Err ( std:: io:: Error :: new (
22+ std:: io:: ErrorKind :: Other ,
23+ "MAVLink2Only" ,
24+ ) ) ,
2125 Ok ( something) => Ok ( something) ,
2226 }
2327 }
@@ -33,7 +37,7 @@ pub struct MAVLinkVehicleHandle<M: mavlink::Message> {
3337 pub thread_rx_channel : std:: sync:: mpsc:: Receiver < ( mavlink:: MavHeader , M ) > ,
3438}
3539
36- impl < M : mavlink:: Message > MAVLinkVehicle < M > {
40+ impl < M : mavlink:: Message + Send + Sync > MAVLinkVehicle < M > {
3741 fn new (
3842 mavlink_connection_string : & str ,
3943 version : mavlink:: MavlinkVersion ,
@@ -55,20 +59,23 @@ impl<M: mavlink::Message> MAVLinkVehicle<M> {
5559 }
5660}
5761
58- impl <
59- M : ' static + mavlink:: Message + std:: fmt:: Debug + From < mavlink:: common:: MavMessage > + Send ,
60- > MAVLinkVehicleHandle < M >
61- {
62+ impl MAVLinkVehicleHandle < mavlink:: ardupilotmega:: MavMessage > {
6263 pub fn new (
6364 connection_string : & str ,
6465 version : mavlink:: MavlinkVersion ,
6566 system_id : u8 ,
6667 component_id : u8 ,
6768 send_initial_heartbeats : bool ,
6869 ) -> Self {
69- let mavlink_vehicle: Arc < Mutex < MAVLinkVehicle < M > > > = Arc :: new ( Mutex :: new (
70- MAVLinkVehicle :: < M > :: new ( connection_string, version, system_id, component_id) ,
71- ) ) ;
70+ let mavlink_vehicle: Arc < Mutex < MAVLinkVehicle < mavlink:: ardupilotmega:: MavMessage > > > =
71+ Arc :: new ( Mutex :: new ( MAVLinkVehicle :: <
72+ mavlink:: ardupilotmega:: MavMessage ,
73+ > :: new (
74+ connection_string,
75+ version,
76+ system_id,
77+ component_id,
78+ ) ) ) ;
7279
7380 // PX4 requires a initial heartbeat to be sent to wake up the connection, otherwise it will
7481 // not send any messages
8895 let heartbeat_mavlink_vehicle = mavlink_vehicle. clone ( ) ;
8996 let receive_message_mavlink_vehicle = mavlink_vehicle. clone ( ) ;
9097
91- let ( tx_channel, rx_channel) = mpsc:: channel :: < ( mavlink:: MavHeader , M ) > ( ) ;
98+ let ( tx_channel, rx_channel) =
99+ mpsc:: channel :: < ( mavlink:: MavHeader , mavlink:: ardupilotmega:: MavMessage ) > ( ) ;
92100
93101 Self {
94102 mavlink_vehicle,
@@ -101,11 +109,9 @@ impl<
101109 }
102110}
103111
104- fn receive_message_loop <
105- M : mavlink:: Message + std:: fmt:: Debug + From < mavlink:: common:: MavMessage > ,
106- > (
107- mavlink_vehicle : Arc < Mutex < MAVLinkVehicle < M > > > ,
108- channel : std:: sync:: mpsc:: Sender < ( mavlink:: MavHeader , M ) > ,
112+ fn receive_message_loop (
113+ mavlink_vehicle : Arc < Mutex < MAVLinkVehicle < mavlink:: ardupilotmega:: MavMessage > > > ,
114+ channel : std:: sync:: mpsc:: Sender < ( mavlink:: MavHeader , mavlink:: ardupilotmega:: MavMessage ) > ,
109115) {
110116 let mavlink_vehicle = mavlink_vehicle. as_ref ( ) . lock ( ) . unwrap ( ) ;
111117
@@ -132,34 +138,30 @@ fn receive_message_loop<
132138 }
133139}
134140
135- fn send_heartbeat < M : mavlink:: Message + From < mavlink:: common:: MavMessage > > (
136- mavlink_vehicle : Arc < Mutex < MAVLinkVehicle < M > > > ,
137- ) {
141+ fn send_heartbeat ( mavlink_vehicle : Arc < Mutex < MAVLinkVehicle < mavlink:: ardupilotmega:: MavMessage > > > ) {
138142 let mavlink_vehicle = mavlink_vehicle. as_ref ( ) . lock ( ) . unwrap ( ) ;
139143 let vehicle = mavlink_vehicle. vehicle . clone ( ) ;
140144 let mut header = mavlink_vehicle. header . lock ( ) . unwrap ( ) ;
141- if let Err ( error) = vehicle. as_ref ( ) . send ( & header, & heartbeat_message ( ) . into ( ) ) {
145+ if let Err ( error) = vehicle. as_ref ( ) . send ( & header, & heartbeat_message ( ) ) {
142146 error ! ( "Failed to send heartbeat: {:?}" , error) ;
143147 }
144148 header. sequence = header. sequence . wrapping_add ( 1 ) ;
145149}
146150
147- fn heartbeat_loop < M : mavlink:: Message + From < mavlink:: common:: MavMessage > > (
148- mavlink_vehicle : Arc < Mutex < MAVLinkVehicle < M > > > ,
149- ) {
151+ fn heartbeat_loop ( mavlink_vehicle : Arc < Mutex < MAVLinkVehicle < mavlink:: ardupilotmega:: MavMessage > > > ) {
150152 loop {
151153 std:: thread:: sleep ( std:: time:: Duration :: from_secs ( 1 ) ) ;
152154 send_heartbeat ( mavlink_vehicle. clone ( ) ) ;
153155 }
154156}
155157
156- pub fn heartbeat_message ( ) -> mavlink:: common :: MavMessage {
157- mavlink:: common :: MavMessage :: HEARTBEAT ( mavlink:: common :: HEARTBEAT_DATA {
158+ pub fn heartbeat_message ( ) -> mavlink:: ardupilotmega :: MavMessage {
159+ mavlink:: ardupilotmega :: MavMessage :: HEARTBEAT ( mavlink:: ardupilotmega :: HEARTBEAT_DATA {
158160 custom_mode : 0 ,
159- mavtype : mavlink:: common :: MavType :: MAV_TYPE_ONBOARD_CONTROLLER ,
160- autopilot : mavlink:: common :: MavAutopilot :: MAV_AUTOPILOT_INVALID ,
161- base_mode : mavlink:: common :: MavModeFlag :: default ( ) ,
162- system_status : mavlink:: common :: MavState :: MAV_STATE_STANDBY ,
161+ mavtype : mavlink:: ardupilotmega :: MavType :: MAV_TYPE_ONBOARD_CONTROLLER ,
162+ autopilot : mavlink:: ardupilotmega :: MavAutopilot :: MAV_AUTOPILOT_INVALID ,
163+ base_mode : mavlink:: ardupilotmega :: MavModeFlag :: default ( ) ,
164+ system_status : mavlink:: ardupilotmega :: MavState :: MAV_STATE_STANDBY ,
163165 mavlink_version : 0x3 ,
164166 } )
165167}
0 commit comments