@@ -1839,6 +1839,70 @@ def executor(agent_id: AgentID) -> None:
1839
1839
ack_timeout ,
1840
1840
)
1841
1841
1842
+ def set_message_interval (
1843
+ self ,
1844
+ message : str ,
1845
+ frequency : float ,
1846
+ response_target : int = 0 ,
1847
+ agent_ids : AgentID | list [AgentID ] | None = None ,
1848
+ retry : bool = False ,
1849
+ message_timeout : float = 2.5 ,
1850
+ ack_timeout : float = 0.5 ,
1851
+ ) -> Future :
1852
+ """
1853
+ Set the interval that a message should be sent at.
1854
+
1855
+ This can be used to increase the frequency or to block messages from being sent.
1856
+
1857
+ :param message: MAVLink message whose message interval should be set
1858
+ :type message: str
1859
+ :param frequency: frequency that the message should be sent at [Hz]
1860
+ :type frequency: float
1861
+ :param response_target: target address of message stream, defaults to 0 (flight
1862
+ stack default)
1863
+ :type response_target: int, optional
1864
+ :param agent_ids: agents that should have, defaults to None
1865
+ :param agent_ids: optional list of target agent IDs, defaults to None
1866
+ :type agent_ids: AgentID | list[AgentID] | None, optional
1867
+ :param retry: retry setting the message interval on acknowledgement failure,
1868
+ defaults to False
1869
+ :type retry: bool, optional
1870
+ :param message_timeout: maximum amount of time allowed to try setting a message
1871
+ interval before a timeout occurs, defaults to 2.5 [s]
1872
+ :type message_timeout: float, optional
1873
+ :param ack_timeout: maximum amount of time allowed per attempt to verify
1874
+ acknowledgement of the message interval setting message, defaults to 0.5 [s]
1875
+ :type ack_timeout: float, optional
1876
+ :return: future message response, if any
1877
+ :rtype: Future
1878
+ """
1879
+
1880
+ def executor (agent_id : AgentID ) -> None :
1881
+ if self ._connection .mavlink_connection is not None :
1882
+ self ._connection .mavlink_connection .mav .command_long_send (
1883
+ agent_id [0 ],
1884
+ agent_id [1 ],
1885
+ mavutil .mavlink .MAV_CMD_SET_MESSAGE_INTERVAL ,
1886
+ 0 ,
1887
+ message ,
1888
+ 1e6 / frequency ,
1889
+ 0 ,
1890
+ 0 ,
1891
+ 0 ,
1892
+ 0 ,
1893
+ response_target ,
1894
+ )
1895
+ return
1896
+
1897
+ return self ._send_command (
1898
+ agent_ids ,
1899
+ executor ,
1900
+ "SET_MESSAGE_INTERVAL" ,
1901
+ retry ,
1902
+ message_timeout ,
1903
+ ack_timeout ,
1904
+ )
1905
+
1842
1906
def get_agent_by_id (self , agent_id : AgentID ) -> Agent | None :
1843
1907
"""
1844
1908
Get the agent with the specified ID (system ID, component ID).
@@ -1880,7 +1944,7 @@ def parse_yaml_mission(self, config_file: str) -> dict:
1880
1944
mission = None
1881
1945
1882
1946
with open (config_file , "r" ) as config :
1883
- mission = yaml .load (config , yaml .FullLoader )["mission" ]
1947
+ mission = yaml .load (config , yaml .FullLoader )["mission" ] # nosec: B506
1884
1948
1885
1949
return mission
1886
1950
@@ -2431,44 +2495,21 @@ def __request_system_time(self, operation: str, key: AgentID, value: Agent) -> N
2431
2495
"""
2432
2496
Request the system time from the agent at the desired rate.
2433
2497
2434
- :param operation: _description_
2498
+ :param operation: dictionary operation performed
2435
2499
:type operation: str
2436
- :param agent_id: _description_
2437
- :type agent_id : AgentID
2438
- :param agent: _description_
2439
- :type agent : Agent
2500
+ :param key: dictionary key (agent ID)
2501
+ :type key : AgentID
2502
+ :param value: dictionary value (agent)
2503
+ :type value : Agent
2440
2504
"""
2441
- REQUEST_FREQ = 0.5 # Hz
2505
+ REQUEST_FREQ = 1.0 # Hz
2442
2506
2443
2507
if operation == "set" and self ._connection .mavlink_connection is not None :
2444
2508
# Request that the agent broadcast its system time at the target interval
2445
2509
# Note that we request that it broadcast to reduce reduncancy in the
2446
2510
# case where multiple agents create a request for this message
2447
-
2448
- def executor (agent_id : AgentID ) -> None :
2449
- if self ._connection .mavlink_connection is not None :
2450
- self ._connection .mavlink_connection .mav .command_long_send (
2451
- agent_id [0 ],
2452
- agent_id [1 ],
2453
- mavutil .mavlink .MAV_CMD_SET_MESSAGE_INTERVAL ,
2454
- 0 ,
2455
- mavutil .mavlink .MAVLINK_MSG_ID_SYSTEM_TIME ,
2456
- 1e6 / REQUEST_FREQ ,
2457
- 0 ,
2458
- 0 ,
2459
- 0 ,
2460
- 0 ,
2461
- 2 ,
2462
- )
2463
- return
2464
-
2465
- future = self ._send_command (
2466
- key ,
2467
- executor ,
2468
- "SET_MESSAGE_INTERVAL" ,
2469
- True ,
2470
- 2.5 ,
2471
- 0.5 ,
2511
+ future = self .set_message_interval (
2512
+ mavutil .mavlink .MAVLINK_MSG_ID_SYSTEM_TIME , REQUEST_FREQ , 2 , key , True
2472
2513
)
2473
2514
2474
2515
while not future .done ():
0 commit comments