diff --git a/mavros/mavros/mission.py b/mavros/mavros/mission.py index dfd57c3cb..37bf38acc 100644 --- a/mavros/mavros/mission.py +++ b/mavros/mavros/mission.py @@ -168,7 +168,6 @@ class QGroundControlPlan(PlanFile): class MissionPluginBase(PluginModule): - _plugin_ns = "mission" _plugin_list_topic = "waypoints" diff --git a/mavros/test/mavros_py/test_param.py b/mavros/test/mavros_py/test_param.py index 2e660d18b..eaf245769 100644 --- a/mavros/test/mavros_py/test_param.py +++ b/mavros/test/mavros_py/test_param.py @@ -60,7 +60,6 @@ def test_ParamDict_set(): ) with patch("mavros.utils.call_set_parameters", MagicMock(return_value={})) as csp: - pm.TEST_B = True pm.TEST_I = 3 pm.TEST_F = 4.0 @@ -71,7 +70,6 @@ def test_ParamDict_set(): assert pm.TEST_F.value == 4.0 with patch("mavros.utils.call_set_parameters", MagicMock(return_value={})) as csp: - pm.setdefault("TEST_D", 5) csp.assert_not_called() @@ -164,7 +162,6 @@ def test_ParamFile_load(file_class, file_name, expected_len): ], ) def test_ParamFile_save(file_class, expected_output): - pf = file_class() pf.parameters = SAVE_PARAMS pf.tgt_system = 2 diff --git a/test_mavros/scripts/test_mavlink_convert_to_rosmsg.py b/test_mavros/scripts/test_mavlink_convert_to_rosmsg.py index 576845b16..71cceb907 100644 --- a/test_mavros/scripts/test_mavlink_convert_to_rosmsg.py +++ b/test_mavros/scripts/test_mavlink_convert_to_rosmsg.py @@ -35,16 +35,21 @@ DRONE_NO = 1 TOPIC_MAVLINK = f"/uas{DRONE_NO}/mavlink_sink" + class fifo(object): - """ A simple buffer """ + """A simple buffer""" + def __init__(self): self.buf = [] + def write(self, data): self.buf += data return len(data) + def read(self): return self.buf.pop(0) + class MyNode(Node): def __init__(self) -> None: node_name = "mav_writer" @@ -62,19 +67,9 @@ def __init__(self) -> None: def set_home(self) -> None: target_system = 0 # broadcast to everyone msg = ardupilotmega.MAVLink_command_long_message( - target_system, - 1, - ardupilotmega.MAV_CMD_DO_SET_HOME, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0 + target_system, 1, ardupilotmega.MAV_CMD_DO_SET_HOME, 0, 0, 0, 0, 0, 0, 0, 0 ) - + msg.pack(self.__mav) current = Clock().now() sec, nanosec = current.seconds_nanoseconds() @@ -83,6 +78,7 @@ def set_home(self) -> None: self.__pub_mavlink.publish(ros_msg) print(ros_msg) + def main(args=None): rclpy.init(args=args) node = MyNode()